diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
index 3f859b1805..f8c6bbcc04 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
@@ -308,6 +308,12 @@
ConfigRawParams.cs
+
+ Form
+
+
+ Setup.cs
+
@@ -569,6 +575,9 @@
Configuration.cs
+
+ Setup.cs
+
3DRradio.cs
diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs
index 03e53b26ba..2840e9b7c8 100644
--- a/Tools/ArdupilotMegaPlanner/Common.cs
+++ b/Tools/ArdupilotMegaPlanner/Common.cs
@@ -429,9 +429,9 @@ namespace ArdupilotMega
#if MAVLINK10
- public static bool translateMode(string modein, ref MAVLink.__mavlink_set_mode_t mode)
+ public static bool translateMode(string modein, ref MAVLink.mavlink_set_mode_t mode)
{
- //MAVLink.__mavlink_set_mode_t mode = new MAVLink.__mavlink_set_mode_t();
+ //MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t();
mode.target_system = MainV2.comPort.sysid;
try
@@ -483,14 +483,14 @@ namespace ArdupilotMega
}
#else
- public static bool translateMode(string modein, ref MAVLink.__mavlink_set_nav_mode_t navmode, ref MAVLink.__mavlink_set_mode_t mode)
+ 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();
+ //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();
+ //MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t();
mode.target = MainV2.comPort.sysid;
try
diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs
index 2970e499b6..edde25fc41 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs
@@ -21,6 +21,17 @@ namespace ArdupilotMega.Controls.BackstageView
private BackstageViewPage _activePage;
private const int ButtonSpacing = 30;
private const int ButtonHeight = 30;
+ public BackstageViewPage SelectedPage { get { return _activePage; } }
+
+ ~BackstageView()
+ {
+ foreach (BackstageViewPage ctl in _pages)
+ {
+ if (ctl.Page != null)
+ ctl.Page.Dispose();
+ }
+ this.Dispose();
+ }
public BackstageView()
{
@@ -160,7 +171,6 @@ namespace ArdupilotMega.Controls.BackstageView
_activePage = page;
ActivatePage(page);
- // Todo: set the link button to be selected looking
}
private void CreateLinkButton(BackstageViewPage page)
diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs
index 420b4544b3..e3e24d9bf0 100644
--- a/Tools/ArdupilotMegaPlanner/CurrentState.cs
+++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs
@@ -334,7 +334,7 @@ namespace ArdupilotMega
if (bytearray != null) // hil
{
- var hil = bytearray.ByteArrayToStructure(6);
+ var hil = bytearray.ByteArrayToStructure(6);
hilch1 = hil.chan1_scaled;
hilch2 = hil.chan2_scaled;
@@ -352,7 +352,7 @@ namespace ArdupilotMega
if (bytearray != null)
{
- var nav = bytearray.ByteArrayToStructure(6);
+ var nav = bytearray.ByteArrayToStructure(6);
nav_roll = nav.nav_roll;
nav_pitch = nav.nav_pitch;
@@ -371,7 +371,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HEARTBEAT];
if (bytearray != null)
{
- var hb = bytearray.ByteArrayToStructure(6);
+ var hb = bytearray.ByteArrayToStructure(6);
string oldmode = mode;
@@ -463,7 +463,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS];
if (bytearray != null)
{
- var sysstatus = bytearray.ByteArrayToStructure(6);
+ var sysstatus = bytearray.ByteArrayToStructure(6);
battery_voltage = sysstatus.voltage_battery;
battery_remaining = sysstatus.battery_remaining;
@@ -478,7 +478,7 @@ namespace ArdupilotMega
if (bytearray != null)
{
- var sysstatus = bytearray.ByteArrayToStructure(6);
+ var sysstatus = bytearray.ByteArrayToStructure(6);
armed = sysstatus.status;
@@ -595,7 +595,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_PRESSURE];
if (bytearray != null)
{
- var pres = bytearray.ByteArrayToStructure(6);
+ var pres = bytearray.ByteArrayToStructure(6);
press_abs = pres.press_abs;
press_temp = pres.temperature;
}
@@ -603,7 +603,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SENSOR_OFFSETS];
if (bytearray != null)
{
- var sensofs = bytearray.ByteArrayToStructure(6);
+ var sensofs = bytearray.ByteArrayToStructure(6);
mag_ofs_x = sensofs.mag_ofs_x;
mag_ofs_y = sensofs.mag_ofs_y;
@@ -627,7 +627,7 @@ namespace ArdupilotMega
if (bytearray != null)
{
- var att = bytearray.ByteArrayToStructure(6);
+ var att = bytearray.ByteArrayToStructure(6);
roll = att.roll * rad2deg;
pitch = att.pitch * rad2deg;
@@ -641,7 +641,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW_INT];
if (bytearray != null)
{
- var gps = bytearray.ByteArrayToStructure(6);
+ var gps = bytearray.ByteArrayToStructure(6);
lat = gps.lat * 1.0e-7f;
lng = gps.lon * 1.0e-7f;
@@ -662,7 +662,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW];
if (bytearray != null)
{
- var gps = bytearray.ByteArrayToStructure(6);
+ var gps = bytearray.ByteArrayToStructure(6);
lat = gps.lat;
lng = gps.lon;
@@ -683,7 +683,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS];
if (bytearray != null)
{
- var gps = bytearray.ByteArrayToStructure(6);
+ var gps = bytearray.ByteArrayToStructure(6);
satcount = gps.satellites_visible;
}
@@ -691,7 +691,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT];
if (bytearray != null)
{
- var loc = bytearray.ByteArrayToStructure(6);
+ var loc = bytearray.ByteArrayToStructure(6);
//alt = loc.alt / 1000.0f;
lat = loc.lat / 10000000.0f;
@@ -701,7 +701,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MISSION_CURRENT];
if (bytearray != null)
{
- var wpcur = bytearray.ByteArrayToStructure(6);
+ var wpcur = bytearray.ByteArrayToStructure(6);
int oldwp = (int)wpno;
@@ -719,7 +719,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION];
if (bytearray != null)
{
- var loc = bytearray.ByteArrayToStructure(6);
+ var loc = bytearray.ByteArrayToStructure(6);
alt = loc.alt;
lat = loc.lat;
lng = loc.lon;
@@ -728,7 +728,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT];
if (bytearray != null)
{
- var wpcur = bytearray.ByteArrayToStructure(6);
+ var wpcur = bytearray.ByteArrayToStructure(6);
int oldwp = (int)wpno;
@@ -746,7 +746,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW];
if (bytearray != null)
{
- var rcin = bytearray.ByteArrayToStructure(6);
+ var rcin = bytearray.ByteArrayToStructure(6);
ch1in = rcin.chan1_raw;
ch2in = rcin.chan2_raw;
@@ -763,7 +763,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW];
if (bytearray != null)
{
- var servoout = bytearray.ByteArrayToStructure(6);
+ var servoout = bytearray.ByteArrayToStructure(6);
ch1out = servoout.servo1_raw;
ch2out = servoout.servo2_raw;
@@ -781,7 +781,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU];
if (bytearray != null)
{
- var imu = bytearray.ByteArrayToStructure(6);
+ var imu = bytearray.ByteArrayToStructure(6);
gx = imu.xgyro;
gy = imu.ygyro;
@@ -801,7 +801,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU];
if (bytearray != null)
{
- var imu = bytearray.ByteArrayToStructure(6);
+ var imu = bytearray.ByteArrayToStructure(6);
gx = imu.xgyro;
gy = imu.ygyro;
@@ -818,7 +818,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD];
if (bytearray != null)
{
- var vfr = bytearray.ByteArrayToStructure(6);
+ var vfr = bytearray.ByteArrayToStructure(6);
groundspeed = vfr.groundspeed;
airspeed = vfr.airspeed;
@@ -843,7 +843,7 @@ namespace ArdupilotMega
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO];
if (bytearray != null)
{
- var mem = bytearray.ByteArrayToStructure(6);
+ var mem = bytearray.ByteArrayToStructure(6);
freemem = mem.freemem;
brklevel = mem.brkval;
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.Designer.cs
new file mode 100644
index 0000000000..24df58eb87
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.Designer.cs
@@ -0,0 +1,134 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class ConfigAccelerometerCalibration
+ {
+ ///
+ /// 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.label28 = new System.Windows.Forms.Label();
+ this.label16 = new System.Windows.Forms.Label();
+ this.label15 = new System.Windows.Forms.Label();
+ this.pictureBoxQuadX = new System.Windows.Forms.PictureBox();
+ this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
+ this.BUT_levelac2 = new ArdupilotMega.MyButton();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).BeginInit();
+ this.SuspendLayout();
+ //
+ // label28
+ //
+ this.label28.AutoSize = true;
+ this.label28.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label28.Location = new System.Drawing.Point(124, 13);
+ this.label28.Name = "label28";
+ this.label28.Size = new System.Drawing.Size(210, 13);
+ this.label28.TabIndex = 15;
+ this.label28.Text = "Level your quad to set default accel offsets";
+ //
+ // label16
+ //
+ this.label16.AutoSize = true;
+ this.label16.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label16.Location = new System.Drawing.Point(124, 308);
+ this.label16.Name = "label16";
+ this.label16.Size = new System.Drawing.Size(192, 26);
+ this.label16.TabIndex = 13;
+ this.label16.Text = "NOTE: images are for presentation only\r\nwill work with hexa\'s etc";
+ //
+ // label15
+ //
+ this.label15.AutoSize = true;
+ this.label15.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label15.Location = new System.Drawing.Point(167, 99);
+ this.label15.Name = "label15";
+ this.label15.Size = new System.Drawing.Size(102, 13);
+ this.label15.TabIndex = 12;
+ this.label15.Text = "Frame Setup (+ or x)";
+ //
+ // pictureBoxQuadX
+ //
+ this.pictureBoxQuadX.Cursor = System.Windows.Forms.Cursors.Hand;
+ this.pictureBoxQuadX.Image = global::ArdupilotMega.Properties.Resources.quadx;
+ this.pictureBoxQuadX.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.pictureBoxQuadX.Location = new System.Drawing.Point(226, 115);
+ this.pictureBoxQuadX.Name = "pictureBoxQuadX";
+ this.pictureBoxQuadX.Size = new System.Drawing.Size(190, 190);
+ this.pictureBoxQuadX.SizeMode = System.Windows.Forms.PictureBoxSizeMode.Zoom;
+ this.pictureBoxQuadX.TabIndex = 11;
+ this.pictureBoxQuadX.TabStop = false;
+ this.pictureBoxQuadX.Click += new System.EventHandler(this.pictureBoxQuadX_Click);
+ //
+ // pictureBoxQuad
+ //
+ this.pictureBoxQuad.Cursor = System.Windows.Forms.Cursors.Hand;
+ this.pictureBoxQuad.Image = global::ArdupilotMega.Properties.Resources.quad;
+ this.pictureBoxQuad.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.pictureBoxQuad.Location = new System.Drawing.Point(19, 115);
+ this.pictureBoxQuad.Name = "pictureBoxQuad";
+ this.pictureBoxQuad.Size = new System.Drawing.Size(190, 190);
+ this.pictureBoxQuad.SizeMode = System.Windows.Forms.PictureBoxSizeMode.Zoom;
+ this.pictureBoxQuad.TabIndex = 10;
+ this.pictureBoxQuad.TabStop = false;
+ //
+ // BUT_levelac2
+ //
+ this.BUT_levelac2.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_levelac2.Location = new System.Drawing.Point(181, 42);
+ this.BUT_levelac2.Name = "BUT_levelac2";
+ this.BUT_levelac2.Size = new System.Drawing.Size(75, 23);
+ this.BUT_levelac2.TabIndex = 14;
+ this.BUT_levelac2.Text = "Level";
+ this.BUT_levelac2.UseVisualStyleBackColor = true;
+ //
+ // ConfigAccelerometerCalibration
+ //
+ this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+ this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+ this.Controls.Add(this.label28);
+ this.Controls.Add(this.label16);
+ this.Controls.Add(this.label15);
+ this.Controls.Add(this.pictureBoxQuadX);
+ this.Controls.Add(this.pictureBoxQuad);
+ this.Controls.Add(this.BUT_levelac2);
+ this.Name = "ConfigAccelerometerCalibration";
+ this.Size = new System.Drawing.Size(439, 356);
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).EndInit();
+ this.ResumeLayout(false);
+ this.PerformLayout();
+
+ }
+
+ #endregion
+
+ private System.Windows.Forms.Label label28;
+ private System.Windows.Forms.Label label16;
+ private System.Windows.Forms.Label label15;
+ private System.Windows.Forms.PictureBox pictureBoxQuadX;
+ private System.Windows.Forms.PictureBox pictureBoxQuad;
+ private MyButton BUT_levelac2;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.cs
new file mode 100644
index 0000000000..fe4fe96bd2
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.cs
@@ -0,0 +1,24 @@
+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.GCSViews.ConfigurationView
+{
+ public partial class ConfigAccelerometerCalibration : UserControl
+ {
+ public ConfigAccelerometerCalibration()
+ {
+ InitializeComponent();
+ }
+
+ private void pictureBoxQuadX_Click(object sender, EventArgs e)
+ {
+
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.resx
new file mode 100644
index 0000000000..7080a7d118
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.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/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
new file mode 100644
index 0000000000..2bcd2ea558
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
@@ -0,0 +1,1247 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class ConfigArducopter
+ {
+ ///
+ /// 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.myLabel3 = new ArdupilotMega.MyLabel();
+ this.TUNE_LOW = new System.Windows.Forms.NumericUpDown();
+ this.TUNE_HIGH = new System.Windows.Forms.NumericUpDown();
+ this.myLabel2 = new ArdupilotMega.MyLabel();
+ this.TUNE = new System.Windows.Forms.ComboBox();
+ this.myLabel1 = new ArdupilotMega.MyLabel();
+ this.CH7_OPT = new System.Windows.Forms.ComboBox();
+ this.groupBox5 = new System.Windows.Forms.GroupBox();
+ this.THR_RATE_D = new System.Windows.Forms.NumericUpDown();
+ this.label29 = new System.Windows.Forms.Label();
+ this.label14 = new System.Windows.Forms.Label();
+ this.THR_RATE_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.THR_RATE_I = new System.Windows.Forms.NumericUpDown();
+ this.label20 = new System.Windows.Forms.Label();
+ this.THR_RATE_P = new System.Windows.Forms.NumericUpDown();
+ this.label25 = new System.Windows.Forms.Label();
+ this.CHK_lockrollpitch = new System.Windows.Forms.CheckBox();
+ this.groupBox4 = new System.Windows.Forms.GroupBox();
+ this.NAV_LAT_D = new System.Windows.Forms.NumericUpDown();
+ this.label27 = new System.Windows.Forms.Label();
+ this.WP_SPEED_MAX = new System.Windows.Forms.NumericUpDown();
+ this.label9 = new System.Windows.Forms.Label();
+ this.NAV_LAT_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label13 = new System.Windows.Forms.Label();
+ this.NAV_LAT_I = new System.Windows.Forms.NumericUpDown();
+ this.label15 = new System.Windows.Forms.Label();
+ this.NAV_LAT_P = new System.Windows.Forms.NumericUpDown();
+ this.label16 = new System.Windows.Forms.Label();
+ this.groupBox6 = new System.Windows.Forms.GroupBox();
+ this.XTRK_GAIN_SC1 = new System.Windows.Forms.NumericUpDown();
+ this.label18 = new System.Windows.Forms.Label();
+ this.groupBox7 = new System.Windows.Forms.GroupBox();
+ this.THR_ALT_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label19 = new System.Windows.Forms.Label();
+ this.THR_ALT_I = new System.Windows.Forms.NumericUpDown();
+ this.label21 = new System.Windows.Forms.Label();
+ this.THR_ALT_P = new System.Windows.Forms.NumericUpDown();
+ this.label22 = new System.Windows.Forms.Label();
+ this.groupBox19 = new System.Windows.Forms.GroupBox();
+ this.HLD_LAT_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label28 = new System.Windows.Forms.Label();
+ this.HLD_LAT_I = new System.Windows.Forms.NumericUpDown();
+ this.label30 = new System.Windows.Forms.Label();
+ this.HLD_LAT_P = new System.Windows.Forms.NumericUpDown();
+ this.label31 = new System.Windows.Forms.Label();
+ this.groupBox20 = new System.Windows.Forms.GroupBox();
+ this.STB_YAW_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label32 = new System.Windows.Forms.Label();
+ this.STB_YAW_I = new System.Windows.Forms.NumericUpDown();
+ this.label34 = new System.Windows.Forms.Label();
+ this.STB_YAW_P = new System.Windows.Forms.NumericUpDown();
+ this.label35 = new System.Windows.Forms.Label();
+ this.groupBox21 = new System.Windows.Forms.GroupBox();
+ this.STAB_D = new System.Windows.Forms.NumericUpDown();
+ this.lblSTAB_D = new System.Windows.Forms.Label();
+ this.STB_PIT_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label36 = new System.Windows.Forms.Label();
+ this.STB_PIT_I = new System.Windows.Forms.NumericUpDown();
+ this.label41 = new System.Windows.Forms.Label();
+ this.STB_PIT_P = new System.Windows.Forms.NumericUpDown();
+ this.label42 = new System.Windows.Forms.Label();
+ this.groupBox22 = new System.Windows.Forms.GroupBox();
+ this.STB_RLL_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label43 = new System.Windows.Forms.Label();
+ this.STB_RLL_I = new System.Windows.Forms.NumericUpDown();
+ this.label45 = new System.Windows.Forms.Label();
+ this.STB_RLL_P = new System.Windows.Forms.NumericUpDown();
+ this.label46 = new System.Windows.Forms.Label();
+ this.groupBox23 = new System.Windows.Forms.GroupBox();
+ this.RATE_YAW_D = new System.Windows.Forms.NumericUpDown();
+ this.label10 = new System.Windows.Forms.Label();
+ this.RATE_YAW_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label47 = new System.Windows.Forms.Label();
+ this.RATE_YAW_I = new System.Windows.Forms.NumericUpDown();
+ this.label77 = new System.Windows.Forms.Label();
+ this.RATE_YAW_P = new System.Windows.Forms.NumericUpDown();
+ this.label82 = new System.Windows.Forms.Label();
+ this.groupBox24 = new System.Windows.Forms.GroupBox();
+ this.RATE_PIT_D = new System.Windows.Forms.NumericUpDown();
+ this.label11 = new System.Windows.Forms.Label();
+ this.RATE_PIT_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label84 = new System.Windows.Forms.Label();
+ this.RATE_PIT_I = new System.Windows.Forms.NumericUpDown();
+ this.label86 = new System.Windows.Forms.Label();
+ this.RATE_PIT_P = new System.Windows.Forms.NumericUpDown();
+ this.label87 = new System.Windows.Forms.Label();
+ this.groupBox25 = new System.Windows.Forms.GroupBox();
+ this.RATE_RLL_D = new System.Windows.Forms.NumericUpDown();
+ this.label17 = new System.Windows.Forms.Label();
+ this.RATE_RLL_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label88 = new System.Windows.Forms.Label();
+ this.RATE_RLL_I = new System.Windows.Forms.NumericUpDown();
+ this.label90 = new System.Windows.Forms.Label();
+ this.RATE_RLL_P = new System.Windows.Forms.NumericUpDown();
+ this.label91 = new System.Windows.Forms.Label();
+ ((System.ComponentModel.ISupportInitialize)(this.TUNE_LOW)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.TUNE_HIGH)).BeginInit();
+ this.groupBox5.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_P)).BeginInit();
+ this.groupBox4.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.WP_SPEED_MAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_P)).BeginInit();
+ this.groupBox6.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC1)).BeginInit();
+ this.groupBox7.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_P)).BeginInit();
+ this.groupBox19.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_P)).BeginInit();
+ this.groupBox20.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).BeginInit();
+ this.groupBox21.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.STAB_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).BeginInit();
+ this.groupBox22.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_P)).BeginInit();
+ this.groupBox23.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_P)).BeginInit();
+ this.groupBox24.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_P)).BeginInit();
+ this.groupBox25.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).BeginInit();
+ this.SuspendLayout();
+ //
+ // myLabel3
+ //
+ this.myLabel3.Location = new System.Drawing.Point(540, 302);
+ this.myLabel3.Name = "myLabel3";
+ this.myLabel3.resize = false;
+ this.myLabel3.Size = new System.Drawing.Size(29, 23);
+ this.myLabel3.TabIndex = 42;
+ this.myLabel3.Text = "Min";
+ //
+ // TUNE_LOW
+ //
+ this.TUNE_LOW.Location = new System.Drawing.Point(575, 305);
+ this.TUNE_LOW.Name = "TUNE_LOW";
+ this.TUNE_LOW.Size = new System.Drawing.Size(51, 20);
+ this.TUNE_LOW.TabIndex = 41;
+ //
+ // TUNE_HIGH
+ //
+ this.TUNE_HIGH.Location = new System.Drawing.Point(665, 305);
+ this.TUNE_HIGH.Name = "TUNE_HIGH";
+ this.TUNE_HIGH.Size = new System.Drawing.Size(46, 20);
+ this.TUNE_HIGH.TabIndex = 40;
+ //
+ // myLabel2
+ //
+ this.myLabel2.Location = new System.Drawing.Point(540, 277);
+ this.myLabel2.Name = "myLabel2";
+ this.myLabel2.resize = false;
+ this.myLabel2.Size = new System.Drawing.Size(53, 23);
+ this.myLabel2.TabIndex = 39;
+ this.myLabel2.Text = "Ch6 Opt";
+ //
+ // TUNE
+ //
+ this.TUNE.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.TUNE.DropDownWidth = 150;
+ this.TUNE.FormattingEnabled = true;
+ this.TUNE.Items.AddRange(new object[] {
+ "CH6_NONE",
+ "CH6_STABILIZE_KP",
+ "CH6_STABILIZE_KI",
+ "CH6_YAW_KP",
+ "CH6_RATE_KP",
+ "CH6_RATE_KI",
+ "CH6_YAW_RATE_KP",
+ "CH6_THROTTLE_KP",
+ "CH6_TOP_BOTTOM_RATIO",
+ "CH6_RELAY",
+ "CH6_TRAVERSE_SPEED",
+ "CH6_NAV_P",
+ "CH6_LOITER_P",
+ "CH6_HELI_EXTERNAL_GYRO",
+ "CH6_THR_HOLD_KP",
+ "CH6_Z_GAIN",
+ "CH6_DAMP",
+ "CH6_OPTFLOW_KP",
+ "CH6_OPTFLOW_KI",
+ "CH6_OPTFLOW_KD",
+ "CH6_NAV_I",
+ "CH6_RATE_KD"});
+ this.TUNE.Location = new System.Drawing.Point(599, 277);
+ this.TUNE.Name = "TUNE";
+ this.TUNE.Size = new System.Drawing.Size(112, 21);
+ this.TUNE.TabIndex = 38;
+ //
+ // myLabel1
+ //
+ this.myLabel1.Location = new System.Drawing.Point(540, 329);
+ this.myLabel1.Name = "myLabel1";
+ this.myLabel1.resize = false;
+ this.myLabel1.Size = new System.Drawing.Size(53, 23);
+ this.myLabel1.TabIndex = 37;
+ this.myLabel1.Text = "Ch7 Opt";
+ //
+ // CH7_OPT
+ //
+ this.CH7_OPT.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CH7_OPT.DropDownWidth = 150;
+ this.CH7_OPT.FormattingEnabled = true;
+ this.CH7_OPT.Items.AddRange(new object[] {
+ "Do Nothing",
+ "",
+ "",
+ "Simple Mode",
+ "RTL",
+ "",
+ "",
+ "Save WP"});
+ this.CH7_OPT.Location = new System.Drawing.Point(599, 329);
+ this.CH7_OPT.Name = "CH7_OPT";
+ this.CH7_OPT.Size = new System.Drawing.Size(112, 21);
+ this.CH7_OPT.TabIndex = 36;
+ //
+ // groupBox5
+ //
+ this.groupBox5.Controls.Add(this.THR_RATE_D);
+ this.groupBox5.Controls.Add(this.label29);
+ this.groupBox5.Controls.Add(this.label14);
+ this.groupBox5.Controls.Add(this.THR_RATE_IMAX);
+ this.groupBox5.Controls.Add(this.THR_RATE_I);
+ this.groupBox5.Controls.Add(this.label20);
+ this.groupBox5.Controls.Add(this.THR_RATE_P);
+ this.groupBox5.Controls.Add(this.label25);
+ this.groupBox5.Location = new System.Drawing.Point(12, 267);
+ this.groupBox5.Name = "groupBox5";
+ this.groupBox5.Size = new System.Drawing.Size(170, 110);
+ this.groupBox5.TabIndex = 35;
+ this.groupBox5.TabStop = false;
+ this.groupBox5.Text = "Throttle Rate";
+ //
+ // THR_RATE_D
+ //
+ this.THR_RATE_D.Location = new System.Drawing.Point(80, 60);
+ this.THR_RATE_D.Name = "THR_RATE_D";
+ this.THR_RATE_D.Size = new System.Drawing.Size(78, 20);
+ this.THR_RATE_D.TabIndex = 14;
+ //
+ // label29
+ //
+ this.label29.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label29.Location = new System.Drawing.Point(6, 63);
+ this.label29.Name = "label29";
+ this.label29.Size = new System.Drawing.Size(10, 13);
+ this.label29.TabIndex = 15;
+ this.label29.Text = "D";
+ //
+ // label14
+ //
+ this.label14.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label14.Location = new System.Drawing.Point(6, 86);
+ this.label14.Name = "label14";
+ this.label14.Size = new System.Drawing.Size(65, 13);
+ this.label14.TabIndex = 16;
+ this.label14.Text = "IMAX";
+ //
+ // THR_RATE_IMAX
+ //
+ this.THR_RATE_IMAX.Location = new System.Drawing.Point(80, 83);
+ this.THR_RATE_IMAX.Name = "THR_RATE_IMAX";
+ this.THR_RATE_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.THR_RATE_IMAX.TabIndex = 11;
+ //
+ // THR_RATE_I
+ //
+ this.THR_RATE_I.Location = new System.Drawing.Point(80, 37);
+ this.THR_RATE_I.Name = "THR_RATE_I";
+ this.THR_RATE_I.Size = new System.Drawing.Size(78, 20);
+ this.THR_RATE_I.TabIndex = 7;
+ //
+ // label20
+ //
+ this.label20.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label20.Location = new System.Drawing.Point(6, 40);
+ this.label20.Name = "label20";
+ this.label20.Size = new System.Drawing.Size(10, 13);
+ this.label20.TabIndex = 14;
+ this.label20.Text = "I";
+ //
+ // THR_RATE_P
+ //
+ this.THR_RATE_P.Location = new System.Drawing.Point(80, 13);
+ this.THR_RATE_P.Name = "THR_RATE_P";
+ this.THR_RATE_P.Size = new System.Drawing.Size(78, 20);
+ this.THR_RATE_P.TabIndex = 5;
+ //
+ // label25
+ //
+ this.label25.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label25.Location = new System.Drawing.Point(6, 16);
+ this.label25.Name = "label25";
+ this.label25.Size = new System.Drawing.Size(14, 13);
+ this.label25.TabIndex = 15;
+ this.label25.Text = "P";
+ //
+ // CHK_lockrollpitch
+ //
+ this.CHK_lockrollpitch.AutoSize = true;
+ this.CHK_lockrollpitch.Checked = true;
+ this.CHK_lockrollpitch.CheckState = System.Windows.Forms.CheckState.Checked;
+ this.CHK_lockrollpitch.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_lockrollpitch.Location = new System.Drawing.Point(9, 247);
+ this.CHK_lockrollpitch.Name = "CHK_lockrollpitch";
+ this.CHK_lockrollpitch.Size = new System.Drawing.Size(154, 17);
+ this.CHK_lockrollpitch.TabIndex = 34;
+ this.CHK_lockrollpitch.Text = "Lock Pitch and Roll Values";
+ this.CHK_lockrollpitch.UseVisualStyleBackColor = true;
+ //
+ // groupBox4
+ //
+ this.groupBox4.Controls.Add(this.NAV_LAT_D);
+ this.groupBox4.Controls.Add(this.label27);
+ this.groupBox4.Controls.Add(this.WP_SPEED_MAX);
+ this.groupBox4.Controls.Add(this.label9);
+ this.groupBox4.Controls.Add(this.NAV_LAT_IMAX);
+ this.groupBox4.Controls.Add(this.label13);
+ this.groupBox4.Controls.Add(this.NAV_LAT_I);
+ this.groupBox4.Controls.Add(this.label15);
+ this.groupBox4.Controls.Add(this.NAV_LAT_P);
+ this.groupBox4.Controls.Add(this.label16);
+ this.groupBox4.Location = new System.Drawing.Point(540, 133);
+ this.groupBox4.Name = "groupBox4";
+ this.groupBox4.Size = new System.Drawing.Size(170, 131);
+ this.groupBox4.TabIndex = 24;
+ this.groupBox4.TabStop = false;
+ this.groupBox4.Text = "Nav WP";
+ //
+ // NAV_LAT_D
+ //
+ this.NAV_LAT_D.Location = new System.Drawing.Point(80, 60);
+ this.NAV_LAT_D.Name = "NAV_LAT_D";
+ this.NAV_LAT_D.Size = new System.Drawing.Size(78, 20);
+ this.NAV_LAT_D.TabIndex = 18;
+ //
+ // label27
+ //
+ this.label27.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label27.Location = new System.Drawing.Point(6, 63);
+ this.label27.Name = "label27";
+ this.label27.Size = new System.Drawing.Size(10, 13);
+ this.label27.TabIndex = 19;
+ this.label27.Text = "D";
+ //
+ // WP_SPEED_MAX
+ //
+ this.WP_SPEED_MAX.Location = new System.Drawing.Point(80, 107);
+ this.WP_SPEED_MAX.Name = "WP_SPEED_MAX";
+ this.WP_SPEED_MAX.Size = new System.Drawing.Size(78, 20);
+ this.WP_SPEED_MAX.TabIndex = 16;
+ //
+ // label9
+ //
+ this.label9.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label9.Location = new System.Drawing.Point(6, 110);
+ this.label9.Name = "label9";
+ this.label9.Size = new System.Drawing.Size(54, 13);
+ this.label9.TabIndex = 17;
+ this.label9.Text = "m/s";
+ //
+ // NAV_LAT_IMAX
+ //
+ this.NAV_LAT_IMAX.Location = new System.Drawing.Point(80, 84);
+ this.NAV_LAT_IMAX.Name = "NAV_LAT_IMAX";
+ this.NAV_LAT_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.NAV_LAT_IMAX.TabIndex = 11;
+ //
+ // label13
+ //
+ this.label13.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label13.Location = new System.Drawing.Point(6, 87);
+ this.label13.Name = "label13";
+ this.label13.Size = new System.Drawing.Size(65, 13);
+ this.label13.TabIndex = 12;
+ this.label13.Text = "IMAX";
+ //
+ // NAV_LAT_I
+ //
+ this.NAV_LAT_I.Location = new System.Drawing.Point(80, 37);
+ this.NAV_LAT_I.Name = "NAV_LAT_I";
+ this.NAV_LAT_I.Size = new System.Drawing.Size(78, 20);
+ this.NAV_LAT_I.TabIndex = 7;
+ //
+ // label15
+ //
+ this.label15.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label15.Location = new System.Drawing.Point(6, 40);
+ this.label15.Name = "label15";
+ this.label15.Size = new System.Drawing.Size(10, 13);
+ this.label15.TabIndex = 14;
+ this.label15.Text = "I";
+ //
+ // NAV_LAT_P
+ //
+ this.NAV_LAT_P.Location = new System.Drawing.Point(80, 13);
+ this.NAV_LAT_P.Name = "NAV_LAT_P";
+ this.NAV_LAT_P.Size = new System.Drawing.Size(78, 20);
+ this.NAV_LAT_P.TabIndex = 5;
+ //
+ // label16
+ //
+ this.label16.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label16.Location = new System.Drawing.Point(6, 16);
+ this.label16.Name = "label16";
+ this.label16.Size = new System.Drawing.Size(14, 13);
+ this.label16.TabIndex = 15;
+ this.label16.Text = "P";
+ //
+ // groupBox6
+ //
+ this.groupBox6.Controls.Add(this.XTRK_GAIN_SC1);
+ this.groupBox6.Controls.Add(this.label18);
+ this.groupBox6.Location = new System.Drawing.Point(364, 267);
+ this.groupBox6.Name = "groupBox6";
+ this.groupBox6.Size = new System.Drawing.Size(170, 43);
+ this.groupBox6.TabIndex = 25;
+ this.groupBox6.TabStop = false;
+ this.groupBox6.Text = "Crosstrack Correction";
+ //
+ // XTRK_GAIN_SC1
+ //
+ this.XTRK_GAIN_SC1.Location = new System.Drawing.Point(80, 13);
+ this.XTRK_GAIN_SC1.Name = "XTRK_GAIN_SC1";
+ this.XTRK_GAIN_SC1.Size = new System.Drawing.Size(78, 20);
+ this.XTRK_GAIN_SC1.TabIndex = 5;
+ //
+ // label18
+ //
+ this.label18.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label18.Location = new System.Drawing.Point(6, 16);
+ this.label18.Name = "label18";
+ this.label18.Size = new System.Drawing.Size(38, 13);
+ this.label18.TabIndex = 15;
+ this.label18.Text = "Gain";
+ //
+ // groupBox7
+ //
+ this.groupBox7.Controls.Add(this.THR_ALT_IMAX);
+ this.groupBox7.Controls.Add(this.label19);
+ this.groupBox7.Controls.Add(this.THR_ALT_I);
+ this.groupBox7.Controls.Add(this.label21);
+ this.groupBox7.Controls.Add(this.THR_ALT_P);
+ this.groupBox7.Controls.Add(this.label22);
+ this.groupBox7.Location = new System.Drawing.Point(188, 267);
+ this.groupBox7.Name = "groupBox7";
+ this.groupBox7.Size = new System.Drawing.Size(170, 110);
+ this.groupBox7.TabIndex = 26;
+ this.groupBox7.TabStop = false;
+ this.groupBox7.Text = "Altitude Hold";
+ //
+ // THR_ALT_IMAX
+ //
+ this.THR_ALT_IMAX.Location = new System.Drawing.Point(80, 63);
+ this.THR_ALT_IMAX.Name = "THR_ALT_IMAX";
+ this.THR_ALT_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.THR_ALT_IMAX.TabIndex = 11;
+ //
+ // label19
+ //
+ this.label19.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label19.Location = new System.Drawing.Point(6, 66);
+ this.label19.Name = "label19";
+ this.label19.Size = new System.Drawing.Size(65, 13);
+ this.label19.TabIndex = 12;
+ this.label19.Text = "IMAX";
+ //
+ // THR_ALT_I
+ //
+ this.THR_ALT_I.Location = new System.Drawing.Point(80, 37);
+ this.THR_ALT_I.Name = "THR_ALT_I";
+ this.THR_ALT_I.Size = new System.Drawing.Size(78, 20);
+ this.THR_ALT_I.TabIndex = 7;
+ //
+ // label21
+ //
+ this.label21.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label21.Location = new System.Drawing.Point(6, 40);
+ this.label21.Name = "label21";
+ this.label21.Size = new System.Drawing.Size(10, 13);
+ this.label21.TabIndex = 14;
+ this.label21.Text = "I";
+ //
+ // THR_ALT_P
+ //
+ this.THR_ALT_P.Location = new System.Drawing.Point(80, 13);
+ this.THR_ALT_P.Name = "THR_ALT_P";
+ this.THR_ALT_P.Size = new System.Drawing.Size(78, 20);
+ this.THR_ALT_P.TabIndex = 5;
+ //
+ // label22
+ //
+ this.label22.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label22.Location = new System.Drawing.Point(6, 16);
+ this.label22.Name = "label22";
+ this.label22.Size = new System.Drawing.Size(14, 13);
+ this.label22.TabIndex = 15;
+ this.label22.Text = "P";
+ //
+ // groupBox19
+ //
+ this.groupBox19.Controls.Add(this.HLD_LAT_IMAX);
+ this.groupBox19.Controls.Add(this.label28);
+ this.groupBox19.Controls.Add(this.HLD_LAT_I);
+ this.groupBox19.Controls.Add(this.label30);
+ this.groupBox19.Controls.Add(this.HLD_LAT_P);
+ this.groupBox19.Controls.Add(this.label31);
+ this.groupBox19.Location = new System.Drawing.Point(537, 13);
+ this.groupBox19.Name = "groupBox19";
+ this.groupBox19.Size = new System.Drawing.Size(170, 95);
+ this.groupBox19.TabIndex = 27;
+ this.groupBox19.TabStop = false;
+ this.groupBox19.Text = "Loiter";
+ //
+ // HLD_LAT_IMAX
+ //
+ this.HLD_LAT_IMAX.Location = new System.Drawing.Point(80, 61);
+ this.HLD_LAT_IMAX.Name = "HLD_LAT_IMAX";
+ this.HLD_LAT_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.HLD_LAT_IMAX.TabIndex = 11;
+ //
+ // label28
+ //
+ this.label28.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label28.Location = new System.Drawing.Point(6, 64);
+ this.label28.Name = "label28";
+ this.label28.Size = new System.Drawing.Size(65, 13);
+ this.label28.TabIndex = 12;
+ this.label28.Text = "IMAX";
+ //
+ // HLD_LAT_I
+ //
+ this.HLD_LAT_I.Location = new System.Drawing.Point(80, 37);
+ this.HLD_LAT_I.Name = "HLD_LAT_I";
+ this.HLD_LAT_I.Size = new System.Drawing.Size(78, 20);
+ this.HLD_LAT_I.TabIndex = 7;
+ //
+ // label30
+ //
+ this.label30.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label30.Location = new System.Drawing.Point(6, 40);
+ this.label30.Name = "label30";
+ this.label30.Size = new System.Drawing.Size(10, 13);
+ this.label30.TabIndex = 14;
+ this.label30.Text = "I";
+ //
+ // HLD_LAT_P
+ //
+ this.HLD_LAT_P.Location = new System.Drawing.Point(80, 13);
+ this.HLD_LAT_P.Name = "HLD_LAT_P";
+ this.HLD_LAT_P.Size = new System.Drawing.Size(78, 20);
+ this.HLD_LAT_P.TabIndex = 5;
+ //
+ // label31
+ //
+ this.label31.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label31.Location = new System.Drawing.Point(6, 16);
+ this.label31.Name = "label31";
+ this.label31.Size = new System.Drawing.Size(14, 13);
+ this.label31.TabIndex = 15;
+ this.label31.Text = "P";
+ //
+ // groupBox20
+ //
+ this.groupBox20.Controls.Add(this.STB_YAW_IMAX);
+ this.groupBox20.Controls.Add(this.label32);
+ this.groupBox20.Controls.Add(this.STB_YAW_I);
+ this.groupBox20.Controls.Add(this.label34);
+ this.groupBox20.Controls.Add(this.STB_YAW_P);
+ this.groupBox20.Controls.Add(this.label35);
+ this.groupBox20.Location = new System.Drawing.Point(364, 13);
+ this.groupBox20.Name = "groupBox20";
+ this.groupBox20.Size = new System.Drawing.Size(170, 95);
+ this.groupBox20.TabIndex = 28;
+ this.groupBox20.TabStop = false;
+ this.groupBox20.Text = "Stabilize Yaw";
+ //
+ // STB_YAW_IMAX
+ //
+ this.STB_YAW_IMAX.Location = new System.Drawing.Point(80, 63);
+ this.STB_YAW_IMAX.Name = "STB_YAW_IMAX";
+ this.STB_YAW_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.STB_YAW_IMAX.TabIndex = 11;
+ //
+ // label32
+ //
+ this.label32.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label32.Location = new System.Drawing.Point(6, 66);
+ this.label32.Name = "label32";
+ this.label32.Size = new System.Drawing.Size(65, 13);
+ this.label32.TabIndex = 12;
+ this.label32.Text = "IMAX ";
+ //
+ // STB_YAW_I
+ //
+ this.STB_YAW_I.Location = new System.Drawing.Point(80, 37);
+ this.STB_YAW_I.Name = "STB_YAW_I";
+ this.STB_YAW_I.Size = new System.Drawing.Size(78, 20);
+ this.STB_YAW_I.TabIndex = 7;
+ //
+ // label34
+ //
+ this.label34.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label34.Location = new System.Drawing.Point(6, 40);
+ this.label34.Name = "label34";
+ this.label34.Size = new System.Drawing.Size(10, 13);
+ this.label34.TabIndex = 14;
+ this.label34.Text = "I";
+ //
+ // STB_YAW_P
+ //
+ this.STB_YAW_P.Location = new System.Drawing.Point(80, 13);
+ this.STB_YAW_P.Name = "STB_YAW_P";
+ this.STB_YAW_P.Size = new System.Drawing.Size(78, 20);
+ this.STB_YAW_P.TabIndex = 5;
+ //
+ // label35
+ //
+ this.label35.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label35.Location = new System.Drawing.Point(6, 16);
+ this.label35.Name = "label35";
+ this.label35.Size = new System.Drawing.Size(14, 13);
+ this.label35.TabIndex = 15;
+ this.label35.Text = "P";
+ //
+ // groupBox21
+ //
+ this.groupBox21.Controls.Add(this.STAB_D);
+ this.groupBox21.Controls.Add(this.lblSTAB_D);
+ this.groupBox21.Controls.Add(this.STB_PIT_IMAX);
+ this.groupBox21.Controls.Add(this.label36);
+ this.groupBox21.Controls.Add(this.STB_PIT_I);
+ this.groupBox21.Controls.Add(this.label41);
+ this.groupBox21.Controls.Add(this.STB_PIT_P);
+ this.groupBox21.Controls.Add(this.label42);
+ this.groupBox21.Location = new System.Drawing.Point(188, 13);
+ this.groupBox21.Name = "groupBox21";
+ this.groupBox21.Size = new System.Drawing.Size(170, 114);
+ this.groupBox21.TabIndex = 29;
+ this.groupBox21.TabStop = false;
+ this.groupBox21.Text = "Stabilize Pitch";
+ //
+ // STAB_D
+ //
+ this.STAB_D.Location = new System.Drawing.Point(80, 88);
+ this.STAB_D.Name = "STAB_D";
+ this.STAB_D.Size = new System.Drawing.Size(78, 20);
+ this.STAB_D.TabIndex = 16;
+ //
+ // lblSTAB_D
+ //
+ this.lblSTAB_D.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.lblSTAB_D.Location = new System.Drawing.Point(6, 91);
+ this.lblSTAB_D.Name = "lblSTAB_D";
+ this.lblSTAB_D.Size = new System.Drawing.Size(65, 13);
+ this.lblSTAB_D.TabIndex = 17;
+ this.lblSTAB_D.Text = "Stabilize D";
+ //
+ // STB_PIT_IMAX
+ //
+ this.STB_PIT_IMAX.Location = new System.Drawing.Point(80, 63);
+ this.STB_PIT_IMAX.Name = "STB_PIT_IMAX";
+ this.STB_PIT_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.STB_PIT_IMAX.TabIndex = 11;
+ //
+ // label36
+ //
+ this.label36.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label36.Location = new System.Drawing.Point(6, 66);
+ this.label36.Name = "label36";
+ this.label36.Size = new System.Drawing.Size(65, 13);
+ this.label36.TabIndex = 12;
+ this.label36.Text = "IMAX";
+ //
+ // STB_PIT_I
+ //
+ this.STB_PIT_I.Location = new System.Drawing.Point(80, 37);
+ this.STB_PIT_I.Name = "STB_PIT_I";
+ this.STB_PIT_I.Size = new System.Drawing.Size(78, 20);
+ this.STB_PIT_I.TabIndex = 7;
+ //
+ // label41
+ //
+ this.label41.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label41.Location = new System.Drawing.Point(6, 40);
+ this.label41.Name = "label41";
+ this.label41.Size = new System.Drawing.Size(10, 13);
+ this.label41.TabIndex = 14;
+ this.label41.Text = "I";
+ //
+ // STB_PIT_P
+ //
+ this.STB_PIT_P.Location = new System.Drawing.Point(80, 13);
+ this.STB_PIT_P.Name = "STB_PIT_P";
+ this.STB_PIT_P.Size = new System.Drawing.Size(78, 20);
+ this.STB_PIT_P.TabIndex = 5;
+ //
+ // label42
+ //
+ this.label42.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label42.Location = new System.Drawing.Point(6, 16);
+ this.label42.Name = "label42";
+ this.label42.Size = new System.Drawing.Size(14, 13);
+ this.label42.TabIndex = 15;
+ this.label42.Text = "P";
+ //
+ // groupBox22
+ //
+ this.groupBox22.Controls.Add(this.STB_RLL_IMAX);
+ this.groupBox22.Controls.Add(this.label43);
+ this.groupBox22.Controls.Add(this.STB_RLL_I);
+ this.groupBox22.Controls.Add(this.label45);
+ this.groupBox22.Controls.Add(this.STB_RLL_P);
+ this.groupBox22.Controls.Add(this.label46);
+ this.groupBox22.Location = new System.Drawing.Point(12, 13);
+ this.groupBox22.Name = "groupBox22";
+ this.groupBox22.Size = new System.Drawing.Size(170, 95);
+ this.groupBox22.TabIndex = 30;
+ this.groupBox22.TabStop = false;
+ this.groupBox22.Text = "Stabilize Roll";
+ //
+ // STB_RLL_IMAX
+ //
+ this.STB_RLL_IMAX.Location = new System.Drawing.Point(80, 63);
+ this.STB_RLL_IMAX.Name = "STB_RLL_IMAX";
+ this.STB_RLL_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.STB_RLL_IMAX.TabIndex = 11;
+ //
+ // label43
+ //
+ this.label43.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label43.Location = new System.Drawing.Point(6, 66);
+ this.label43.Name = "label43";
+ this.label43.Size = new System.Drawing.Size(65, 13);
+ this.label43.TabIndex = 12;
+ this.label43.Text = "IMAX";
+ //
+ // STB_RLL_I
+ //
+ this.STB_RLL_I.Location = new System.Drawing.Point(80, 37);
+ this.STB_RLL_I.Name = "STB_RLL_I";
+ this.STB_RLL_I.Size = new System.Drawing.Size(78, 20);
+ this.STB_RLL_I.TabIndex = 7;
+ //
+ // label45
+ //
+ this.label45.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label45.Location = new System.Drawing.Point(6, 40);
+ this.label45.Name = "label45";
+ this.label45.Size = new System.Drawing.Size(10, 13);
+ this.label45.TabIndex = 14;
+ this.label45.Text = "I";
+ //
+ // STB_RLL_P
+ //
+ this.STB_RLL_P.Location = new System.Drawing.Point(80, 13);
+ this.STB_RLL_P.Name = "STB_RLL_P";
+ this.STB_RLL_P.Size = new System.Drawing.Size(78, 20);
+ this.STB_RLL_P.TabIndex = 5;
+ //
+ // label46
+ //
+ this.label46.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label46.Location = new System.Drawing.Point(6, 16);
+ this.label46.Name = "label46";
+ this.label46.Size = new System.Drawing.Size(14, 13);
+ this.label46.TabIndex = 15;
+ this.label46.Text = "P";
+ //
+ // groupBox23
+ //
+ this.groupBox23.Controls.Add(this.RATE_YAW_D);
+ this.groupBox23.Controls.Add(this.label10);
+ this.groupBox23.Controls.Add(this.RATE_YAW_IMAX);
+ this.groupBox23.Controls.Add(this.label47);
+ this.groupBox23.Controls.Add(this.RATE_YAW_I);
+ this.groupBox23.Controls.Add(this.label77);
+ this.groupBox23.Controls.Add(this.RATE_YAW_P);
+ this.groupBox23.Controls.Add(this.label82);
+ this.groupBox23.Location = new System.Drawing.Point(364, 133);
+ this.groupBox23.Name = "groupBox23";
+ this.groupBox23.Size = new System.Drawing.Size(170, 108);
+ this.groupBox23.TabIndex = 31;
+ this.groupBox23.TabStop = false;
+ this.groupBox23.Text = "Rate Yaw";
+ //
+ // RATE_YAW_D
+ //
+ this.RATE_YAW_D.Location = new System.Drawing.Point(80, 60);
+ this.RATE_YAW_D.Name = "RATE_YAW_D";
+ this.RATE_YAW_D.Size = new System.Drawing.Size(78, 20);
+ this.RATE_YAW_D.TabIndex = 8;
+ //
+ // label10
+ //
+ this.label10.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label10.Location = new System.Drawing.Point(6, 63);
+ this.label10.Name = "label10";
+ this.label10.Size = new System.Drawing.Size(10, 13);
+ this.label10.TabIndex = 9;
+ this.label10.Text = "D";
+ //
+ // RATE_YAW_IMAX
+ //
+ this.RATE_YAW_IMAX.Location = new System.Drawing.Point(80, 84);
+ this.RATE_YAW_IMAX.Name = "RATE_YAW_IMAX";
+ this.RATE_YAW_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.RATE_YAW_IMAX.TabIndex = 0;
+ //
+ // label47
+ //
+ this.label47.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label47.Location = new System.Drawing.Point(6, 87);
+ this.label47.Name = "label47";
+ this.label47.Size = new System.Drawing.Size(65, 13);
+ this.label47.TabIndex = 1;
+ this.label47.Text = "IMAX";
+ //
+ // RATE_YAW_I
+ //
+ this.RATE_YAW_I.Location = new System.Drawing.Point(80, 37);
+ this.RATE_YAW_I.Name = "RATE_YAW_I";
+ this.RATE_YAW_I.Size = new System.Drawing.Size(78, 20);
+ this.RATE_YAW_I.TabIndex = 4;
+ //
+ // label77
+ //
+ this.label77.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label77.Location = new System.Drawing.Point(6, 40);
+ this.label77.Name = "label77";
+ this.label77.Size = new System.Drawing.Size(10, 13);
+ this.label77.TabIndex = 5;
+ this.label77.Text = "I";
+ //
+ // RATE_YAW_P
+ //
+ this.RATE_YAW_P.Location = new System.Drawing.Point(80, 13);
+ this.RATE_YAW_P.Name = "RATE_YAW_P";
+ this.RATE_YAW_P.Size = new System.Drawing.Size(78, 20);
+ this.RATE_YAW_P.TabIndex = 6;
+ //
+ // label82
+ //
+ this.label82.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label82.Location = new System.Drawing.Point(6, 16);
+ this.label82.Name = "label82";
+ this.label82.Size = new System.Drawing.Size(14, 13);
+ this.label82.TabIndex = 7;
+ this.label82.Text = "P";
+ //
+ // groupBox24
+ //
+ this.groupBox24.Controls.Add(this.RATE_PIT_D);
+ this.groupBox24.Controls.Add(this.label11);
+ this.groupBox24.Controls.Add(this.RATE_PIT_IMAX);
+ this.groupBox24.Controls.Add(this.label84);
+ this.groupBox24.Controls.Add(this.RATE_PIT_I);
+ this.groupBox24.Controls.Add(this.label86);
+ this.groupBox24.Controls.Add(this.RATE_PIT_P);
+ this.groupBox24.Controls.Add(this.label87);
+ this.groupBox24.Location = new System.Drawing.Point(188, 133);
+ this.groupBox24.Name = "groupBox24";
+ this.groupBox24.Size = new System.Drawing.Size(170, 108);
+ this.groupBox24.TabIndex = 32;
+ this.groupBox24.TabStop = false;
+ this.groupBox24.Text = "Rate Pitch";
+ //
+ // RATE_PIT_D
+ //
+ this.RATE_PIT_D.Location = new System.Drawing.Point(80, 60);
+ this.RATE_PIT_D.Name = "RATE_PIT_D";
+ this.RATE_PIT_D.Size = new System.Drawing.Size(78, 20);
+ this.RATE_PIT_D.TabIndex = 10;
+ //
+ // label11
+ //
+ this.label11.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label11.Location = new System.Drawing.Point(6, 63);
+ this.label11.Name = "label11";
+ this.label11.Size = new System.Drawing.Size(10, 13);
+ this.label11.TabIndex = 11;
+ this.label11.Text = "D";
+ //
+ // RATE_PIT_IMAX
+ //
+ this.RATE_PIT_IMAX.Location = new System.Drawing.Point(80, 83);
+ this.RATE_PIT_IMAX.Name = "RATE_PIT_IMAX";
+ this.RATE_PIT_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.RATE_PIT_IMAX.TabIndex = 0;
+ //
+ // label84
+ //
+ this.label84.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label84.Location = new System.Drawing.Point(6, 86);
+ this.label84.Name = "label84";
+ this.label84.Size = new System.Drawing.Size(65, 13);
+ this.label84.TabIndex = 1;
+ this.label84.Text = "IMAX";
+ //
+ // RATE_PIT_I
+ //
+ this.RATE_PIT_I.Location = new System.Drawing.Point(80, 37);
+ this.RATE_PIT_I.Name = "RATE_PIT_I";
+ this.RATE_PIT_I.Size = new System.Drawing.Size(78, 20);
+ this.RATE_PIT_I.TabIndex = 4;
+ //
+ // label86
+ //
+ this.label86.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label86.Location = new System.Drawing.Point(6, 40);
+ this.label86.Name = "label86";
+ this.label86.Size = new System.Drawing.Size(10, 13);
+ this.label86.TabIndex = 5;
+ this.label86.Text = "I";
+ //
+ // RATE_PIT_P
+ //
+ this.RATE_PIT_P.Location = new System.Drawing.Point(80, 13);
+ this.RATE_PIT_P.Name = "RATE_PIT_P";
+ this.RATE_PIT_P.Size = new System.Drawing.Size(78, 20);
+ this.RATE_PIT_P.TabIndex = 6;
+ //
+ // label87
+ //
+ this.label87.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label87.Location = new System.Drawing.Point(6, 16);
+ this.label87.Name = "label87";
+ this.label87.Size = new System.Drawing.Size(14, 13);
+ this.label87.TabIndex = 7;
+ this.label87.Text = "P";
+ //
+ // groupBox25
+ //
+ this.groupBox25.Controls.Add(this.RATE_RLL_D);
+ this.groupBox25.Controls.Add(this.label17);
+ this.groupBox25.Controls.Add(this.RATE_RLL_IMAX);
+ this.groupBox25.Controls.Add(this.label88);
+ this.groupBox25.Controls.Add(this.RATE_RLL_I);
+ this.groupBox25.Controls.Add(this.label90);
+ this.groupBox25.Controls.Add(this.RATE_RLL_P);
+ this.groupBox25.Controls.Add(this.label91);
+ this.groupBox25.Location = new System.Drawing.Point(12, 133);
+ this.groupBox25.Name = "groupBox25";
+ this.groupBox25.Size = new System.Drawing.Size(170, 108);
+ this.groupBox25.TabIndex = 33;
+ this.groupBox25.TabStop = false;
+ this.groupBox25.Text = "Rate Roll";
+ //
+ // RATE_RLL_D
+ //
+ this.RATE_RLL_D.Location = new System.Drawing.Point(80, 60);
+ this.RATE_RLL_D.Name = "RATE_RLL_D";
+ this.RATE_RLL_D.Size = new System.Drawing.Size(78, 20);
+ this.RATE_RLL_D.TabIndex = 12;
+ //
+ // label17
+ //
+ this.label17.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label17.Location = new System.Drawing.Point(6, 63);
+ this.label17.Name = "label17";
+ this.label17.Size = new System.Drawing.Size(10, 13);
+ this.label17.TabIndex = 13;
+ this.label17.Text = "D";
+ //
+ // RATE_RLL_IMAX
+ //
+ this.RATE_RLL_IMAX.Location = new System.Drawing.Point(80, 83);
+ this.RATE_RLL_IMAX.Name = "RATE_RLL_IMAX";
+ this.RATE_RLL_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.RATE_RLL_IMAX.TabIndex = 0;
+ //
+ // label88
+ //
+ this.label88.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label88.Location = new System.Drawing.Point(6, 86);
+ this.label88.Name = "label88";
+ this.label88.Size = new System.Drawing.Size(68, 13);
+ this.label88.TabIndex = 1;
+ this.label88.Text = "IMAX";
+ //
+ // RATE_RLL_I
+ //
+ this.RATE_RLL_I.Location = new System.Drawing.Point(80, 37);
+ this.RATE_RLL_I.Name = "RATE_RLL_I";
+ this.RATE_RLL_I.Size = new System.Drawing.Size(78, 20);
+ this.RATE_RLL_I.TabIndex = 4;
+ //
+ // label90
+ //
+ this.label90.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label90.Location = new System.Drawing.Point(6, 40);
+ this.label90.Name = "label90";
+ this.label90.Size = new System.Drawing.Size(10, 13);
+ this.label90.TabIndex = 5;
+ this.label90.Text = "I";
+ //
+ // RATE_RLL_P
+ //
+ this.RATE_RLL_P.Location = new System.Drawing.Point(80, 13);
+ this.RATE_RLL_P.Name = "RATE_RLL_P";
+ this.RATE_RLL_P.Size = new System.Drawing.Size(78, 20);
+ this.RATE_RLL_P.TabIndex = 6;
+ //
+ // label91
+ //
+ this.label91.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label91.Location = new System.Drawing.Point(6, 16);
+ this.label91.Name = "label91";
+ this.label91.Size = new System.Drawing.Size(14, 13);
+ this.label91.TabIndex = 7;
+ this.label91.Text = "P";
+ //
+ // ConfigArducopter
+ //
+ this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+ this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+ this.Controls.Add(this.myLabel3);
+ this.Controls.Add(this.TUNE_LOW);
+ this.Controls.Add(this.TUNE_HIGH);
+ this.Controls.Add(this.myLabel2);
+ this.Controls.Add(this.TUNE);
+ this.Controls.Add(this.myLabel1);
+ this.Controls.Add(this.CH7_OPT);
+ this.Controls.Add(this.groupBox5);
+ this.Controls.Add(this.CHK_lockrollpitch);
+ this.Controls.Add(this.groupBox4);
+ this.Controls.Add(this.groupBox6);
+ this.Controls.Add(this.groupBox7);
+ this.Controls.Add(this.groupBox19);
+ this.Controls.Add(this.groupBox20);
+ this.Controls.Add(this.groupBox21);
+ this.Controls.Add(this.groupBox22);
+ this.Controls.Add(this.groupBox23);
+ this.Controls.Add(this.groupBox24);
+ this.Controls.Add(this.groupBox25);
+ this.Name = "ConfigArducopter";
+ this.Size = new System.Drawing.Size(728, 393);
+ ((System.ComponentModel.ISupportInitialize)(this.TUNE_LOW)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.TUNE_HIGH)).EndInit();
+ this.groupBox5.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_P)).EndInit();
+ this.groupBox4.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.WP_SPEED_MAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_P)).EndInit();
+ this.groupBox6.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC1)).EndInit();
+ this.groupBox7.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_P)).EndInit();
+ this.groupBox19.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_P)).EndInit();
+ this.groupBox20.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).EndInit();
+ this.groupBox21.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.STAB_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).EndInit();
+ this.groupBox22.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_P)).EndInit();
+ this.groupBox23.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_P)).EndInit();
+ this.groupBox24.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_P)).EndInit();
+ this.groupBox25.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).EndInit();
+ this.ResumeLayout(false);
+ this.PerformLayout();
+
+ }
+
+ #endregion
+
+ private MyLabel myLabel3;
+ private System.Windows.Forms.NumericUpDown TUNE_LOW;
+ private System.Windows.Forms.NumericUpDown TUNE_HIGH;
+ private MyLabel myLabel2;
+ private System.Windows.Forms.ComboBox TUNE;
+ private MyLabel myLabel1;
+ private System.Windows.Forms.ComboBox CH7_OPT;
+ private System.Windows.Forms.GroupBox groupBox5;
+ private System.Windows.Forms.NumericUpDown THR_RATE_D;
+ private System.Windows.Forms.Label label29;
+ private System.Windows.Forms.Label label14;
+ private System.Windows.Forms.NumericUpDown THR_RATE_IMAX;
+ private System.Windows.Forms.NumericUpDown THR_RATE_I;
+ private System.Windows.Forms.Label label20;
+ private System.Windows.Forms.NumericUpDown THR_RATE_P;
+ private System.Windows.Forms.Label label25;
+ private System.Windows.Forms.CheckBox CHK_lockrollpitch;
+ private System.Windows.Forms.GroupBox groupBox4;
+ private System.Windows.Forms.NumericUpDown NAV_LAT_D;
+ private System.Windows.Forms.Label label27;
+ private System.Windows.Forms.NumericUpDown WP_SPEED_MAX;
+ private System.Windows.Forms.Label label9;
+ private System.Windows.Forms.NumericUpDown NAV_LAT_IMAX;
+ private System.Windows.Forms.Label label13;
+ private System.Windows.Forms.NumericUpDown NAV_LAT_I;
+ private System.Windows.Forms.Label label15;
+ private System.Windows.Forms.NumericUpDown NAV_LAT_P;
+ private System.Windows.Forms.Label label16;
+ private System.Windows.Forms.GroupBox groupBox6;
+ private System.Windows.Forms.NumericUpDown XTRK_GAIN_SC1;
+ private System.Windows.Forms.Label label18;
+ private System.Windows.Forms.GroupBox groupBox7;
+ private System.Windows.Forms.NumericUpDown THR_ALT_IMAX;
+ private System.Windows.Forms.Label label19;
+ private System.Windows.Forms.NumericUpDown THR_ALT_I;
+ private System.Windows.Forms.Label label21;
+ private System.Windows.Forms.NumericUpDown THR_ALT_P;
+ private System.Windows.Forms.Label label22;
+ private System.Windows.Forms.GroupBox groupBox19;
+ private System.Windows.Forms.NumericUpDown HLD_LAT_IMAX;
+ private System.Windows.Forms.Label label28;
+ private System.Windows.Forms.NumericUpDown HLD_LAT_I;
+ private System.Windows.Forms.Label label30;
+ private System.Windows.Forms.NumericUpDown HLD_LAT_P;
+ private System.Windows.Forms.Label label31;
+ private System.Windows.Forms.GroupBox groupBox20;
+ private System.Windows.Forms.NumericUpDown STB_YAW_IMAX;
+ private System.Windows.Forms.Label label32;
+ private System.Windows.Forms.NumericUpDown STB_YAW_I;
+ private System.Windows.Forms.Label label34;
+ private System.Windows.Forms.NumericUpDown STB_YAW_P;
+ private System.Windows.Forms.Label label35;
+ private System.Windows.Forms.GroupBox groupBox21;
+ private System.Windows.Forms.NumericUpDown STAB_D;
+ private System.Windows.Forms.Label lblSTAB_D;
+ private System.Windows.Forms.NumericUpDown STB_PIT_IMAX;
+ private System.Windows.Forms.Label label36;
+ private System.Windows.Forms.NumericUpDown STB_PIT_I;
+ private System.Windows.Forms.Label label41;
+ private System.Windows.Forms.NumericUpDown STB_PIT_P;
+ private System.Windows.Forms.Label label42;
+ private System.Windows.Forms.GroupBox groupBox22;
+ private System.Windows.Forms.NumericUpDown STB_RLL_IMAX;
+ private System.Windows.Forms.Label label43;
+ private System.Windows.Forms.NumericUpDown STB_RLL_I;
+ private System.Windows.Forms.Label label45;
+ private System.Windows.Forms.NumericUpDown STB_RLL_P;
+ private System.Windows.Forms.Label label46;
+ private System.Windows.Forms.GroupBox groupBox23;
+ private System.Windows.Forms.NumericUpDown RATE_YAW_D;
+ private System.Windows.Forms.Label label10;
+ private System.Windows.Forms.NumericUpDown RATE_YAW_IMAX;
+ private System.Windows.Forms.Label label47;
+ private System.Windows.Forms.NumericUpDown RATE_YAW_I;
+ private System.Windows.Forms.Label label77;
+ private System.Windows.Forms.NumericUpDown RATE_YAW_P;
+ private System.Windows.Forms.Label label82;
+ private System.Windows.Forms.GroupBox groupBox24;
+ private System.Windows.Forms.NumericUpDown RATE_PIT_D;
+ private System.Windows.Forms.Label label11;
+ private System.Windows.Forms.NumericUpDown RATE_PIT_IMAX;
+ private System.Windows.Forms.Label label84;
+ private System.Windows.Forms.NumericUpDown RATE_PIT_I;
+ private System.Windows.Forms.Label label86;
+ private System.Windows.Forms.NumericUpDown RATE_PIT_P;
+ private System.Windows.Forms.Label label87;
+ private System.Windows.Forms.GroupBox groupBox25;
+ private System.Windows.Forms.NumericUpDown RATE_RLL_D;
+ private System.Windows.Forms.Label label17;
+ private System.Windows.Forms.NumericUpDown RATE_RLL_IMAX;
+ private System.Windows.Forms.Label label88;
+ private System.Windows.Forms.NumericUpDown RATE_RLL_I;
+ private System.Windows.Forms.Label label90;
+ private System.Windows.Forms.NumericUpDown RATE_RLL_P;
+ private System.Windows.Forms.Label label91;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs
new file mode 100644
index 0000000000..772230d335
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs
@@ -0,0 +1,19 @@
+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.GCSViews.ConfigurationView
+{
+ public partial class ConfigArducopter : UserControl
+ {
+ public ConfigArducopter()
+ {
+ InitializeComponent();
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx
new file mode 100644
index 0000000000..7080a7d118
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.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/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs
new file mode 100644
index 0000000000..a6928f5b21
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs
@@ -0,0 +1,1270 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class ConfigArduplane
+ {
+ ///
+ /// 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.groupBox3 = new System.Windows.Forms.GroupBox();
+ this.THR_FS_VALUE = new System.Windows.Forms.NumericUpDown();
+ this.label5 = new System.Windows.Forms.Label();
+ this.THR_MAX = new System.Windows.Forms.NumericUpDown();
+ this.label6 = new System.Windows.Forms.Label();
+ this.THR_MIN = new System.Windows.Forms.NumericUpDown();
+ this.label7 = new System.Windows.Forms.Label();
+ this.TRIM_THROTTLE = new System.Windows.Forms.NumericUpDown();
+ this.label8 = new System.Windows.Forms.Label();
+ this.groupBox1 = new System.Windows.Forms.GroupBox();
+ this.ARSPD_RATIO = new System.Windows.Forms.NumericUpDown();
+ this.label1 = new System.Windows.Forms.Label();
+ this.ARSPD_FBW_MAX = new System.Windows.Forms.NumericUpDown();
+ this.label2 = new System.Windows.Forms.Label();
+ this.ARSPD_FBW_MIN = new System.Windows.Forms.NumericUpDown();
+ this.label3 = new System.Windows.Forms.Label();
+ this.TRIM_ARSPD_CM = new System.Windows.Forms.NumericUpDown();
+ this.label4 = new System.Windows.Forms.Label();
+ this.groupBox2 = new System.Windows.Forms.GroupBox();
+ this.LIM_PITCH_MIN = new System.Windows.Forms.NumericUpDown();
+ this.label39 = new System.Windows.Forms.Label();
+ this.LIM_PITCH_MAX = new System.Windows.Forms.NumericUpDown();
+ this.label38 = new System.Windows.Forms.Label();
+ this.LIM_ROLL_CD = new System.Windows.Forms.NumericUpDown();
+ this.label37 = new System.Windows.Forms.Label();
+ this.groupBox15 = new System.Windows.Forms.GroupBox();
+ this.XTRK_ANGLE_CD = new System.Windows.Forms.NumericUpDown();
+ this.label79 = new System.Windows.Forms.Label();
+ this.XTRK_GAIN_SC = new System.Windows.Forms.NumericUpDown();
+ this.label80 = new System.Windows.Forms.Label();
+ this.groupBox16 = new System.Windows.Forms.GroupBox();
+ this.KFF_PTCH2THR = new System.Windows.Forms.NumericUpDown();
+ this.label83 = new System.Windows.Forms.Label();
+ this.KFF_RDDRMIX = new System.Windows.Forms.NumericUpDown();
+ this.label78 = new System.Windows.Forms.Label();
+ this.KFF_PTCHCOMP = new System.Windows.Forms.NumericUpDown();
+ this.label81 = new System.Windows.Forms.Label();
+ this.groupBox14 = new System.Windows.Forms.GroupBox();
+ this.ENRGY2THR_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label73 = new System.Windows.Forms.Label();
+ this.ENRGY2THR_D = new System.Windows.Forms.NumericUpDown();
+ this.label74 = new System.Windows.Forms.Label();
+ this.ENRGY2THR_I = new System.Windows.Forms.NumericUpDown();
+ this.label75 = new System.Windows.Forms.Label();
+ this.ENRGY2THR_P = new System.Windows.Forms.NumericUpDown();
+ this.label76 = new System.Windows.Forms.Label();
+ this.groupBox13 = new System.Windows.Forms.GroupBox();
+ this.ALT2PTCH_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label69 = new System.Windows.Forms.Label();
+ this.ALT2PTCH_D = new System.Windows.Forms.NumericUpDown();
+ this.label70 = new System.Windows.Forms.Label();
+ this.ALT2PTCH_I = new System.Windows.Forms.NumericUpDown();
+ this.label71 = new System.Windows.Forms.Label();
+ this.ALT2PTCH_P = new System.Windows.Forms.NumericUpDown();
+ this.label72 = new System.Windows.Forms.Label();
+ this.groupBox12 = new System.Windows.Forms.GroupBox();
+ this.ARSP2PTCH_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label65 = new System.Windows.Forms.Label();
+ this.ARSP2PTCH_D = new System.Windows.Forms.NumericUpDown();
+ this.label66 = new System.Windows.Forms.Label();
+ this.ARSP2PTCH_I = new System.Windows.Forms.NumericUpDown();
+ this.label67 = new System.Windows.Forms.Label();
+ this.ARSP2PTCH_P = new System.Windows.Forms.NumericUpDown();
+ this.label68 = new System.Windows.Forms.Label();
+ this.groupBox11 = new System.Windows.Forms.GroupBox();
+ this.HDNG2RLL_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label61 = new System.Windows.Forms.Label();
+ this.HDNG2RLL_D = new System.Windows.Forms.NumericUpDown();
+ this.label62 = new System.Windows.Forms.Label();
+ this.HDNG2RLL_I = new System.Windows.Forms.NumericUpDown();
+ this.label63 = new System.Windows.Forms.Label();
+ this.HDNG2RLL_P = new System.Windows.Forms.NumericUpDown();
+ this.label64 = new System.Windows.Forms.Label();
+ this.groupBox10 = new System.Windows.Forms.GroupBox();
+ this.YW2SRV_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label57 = new System.Windows.Forms.Label();
+ this.YW2SRV_D = new System.Windows.Forms.NumericUpDown();
+ this.label58 = new System.Windows.Forms.Label();
+ this.YW2SRV_I = new System.Windows.Forms.NumericUpDown();
+ this.label59 = new System.Windows.Forms.Label();
+ this.YW2SRV_P = new System.Windows.Forms.NumericUpDown();
+ this.label60 = new System.Windows.Forms.Label();
+ this.groupBox9 = new System.Windows.Forms.GroupBox();
+ this.PTCH2SRV_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label53 = new System.Windows.Forms.Label();
+ this.PTCH2SRV_D = new System.Windows.Forms.NumericUpDown();
+ this.label54 = new System.Windows.Forms.Label();
+ this.PTCH2SRV_I = new System.Windows.Forms.NumericUpDown();
+ this.label55 = new System.Windows.Forms.Label();
+ this.PTCH2SRV_P = new System.Windows.Forms.NumericUpDown();
+ this.label56 = new System.Windows.Forms.Label();
+ this.groupBox8 = new System.Windows.Forms.GroupBox();
+ this.RLL2SRV_IMAX = new System.Windows.Forms.NumericUpDown();
+ this.label49 = new System.Windows.Forms.Label();
+ this.RLL2SRV_D = new System.Windows.Forms.NumericUpDown();
+ this.label50 = new System.Windows.Forms.Label();
+ this.RLL2SRV_I = new System.Windows.Forms.NumericUpDown();
+ this.label51 = new System.Windows.Forms.Label();
+ this.RLL2SRV_P = new System.Windows.Forms.NumericUpDown();
+ this.label52 = new System.Windows.Forms.Label();
+ this.groupBox3.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_FS_VALUE)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_MAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_MIN)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.TRIM_THROTTLE)).BeginInit();
+ this.groupBox1.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSPD_RATIO)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MIN)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.TRIM_ARSPD_CM)).BeginInit();
+ this.groupBox2.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MIN)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.LIM_ROLL_CD)).BeginInit();
+ this.groupBox15.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC)).BeginInit();
+ this.groupBox16.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCH2THR)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.KFF_RDDRMIX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCHCOMP)).BeginInit();
+ this.groupBox14.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_P)).BeginInit();
+ this.groupBox13.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_P)).BeginInit();
+ this.groupBox12.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_P)).BeginInit();
+ this.groupBox11.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_P)).BeginInit();
+ this.groupBox10.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_P)).BeginInit();
+ this.groupBox9.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_P)).BeginInit();
+ this.groupBox8.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_IMAX)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_D)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_I)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).BeginInit();
+ this.SuspendLayout();
+ //
+ // groupBox3
+ //
+ this.groupBox3.Controls.Add(this.THR_FS_VALUE);
+ this.groupBox3.Controls.Add(this.label5);
+ this.groupBox3.Controls.Add(this.THR_MAX);
+ this.groupBox3.Controls.Add(this.label6);
+ this.groupBox3.Controls.Add(this.THR_MIN);
+ this.groupBox3.Controls.Add(this.label7);
+ this.groupBox3.Controls.Add(this.TRIM_THROTTLE);
+ this.groupBox3.Controls.Add(this.label8);
+ this.groupBox3.Location = new System.Drawing.Point(413, 231);
+ this.groupBox3.Name = "groupBox3";
+ this.groupBox3.Size = new System.Drawing.Size(195, 108);
+ this.groupBox3.TabIndex = 12;
+ this.groupBox3.TabStop = false;
+ this.groupBox3.Text = "Throttle 0-100%";
+ //
+ // THR_FS_VALUE
+ //
+ this.THR_FS_VALUE.Location = new System.Drawing.Point(111, 82);
+ this.THR_FS_VALUE.Name = "THR_FS_VALUE";
+ this.THR_FS_VALUE.Size = new System.Drawing.Size(78, 20);
+ this.THR_FS_VALUE.TabIndex = 11;
+ //
+ // label5
+ //
+ this.label5.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label5.Location = new System.Drawing.Point(6, 86);
+ this.label5.Name = "label5";
+ this.label5.Size = new System.Drawing.Size(50, 13);
+ this.label5.TabIndex = 12;
+ this.label5.Text = "FS Value";
+ //
+ // THR_MAX
+ //
+ this.THR_MAX.Location = new System.Drawing.Point(111, 59);
+ this.THR_MAX.Name = "THR_MAX";
+ this.THR_MAX.Size = new System.Drawing.Size(78, 20);
+ this.THR_MAX.TabIndex = 9;
+ //
+ // label6
+ //
+ this.label6.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label6.Location = new System.Drawing.Point(6, 63);
+ this.label6.Name = "label6";
+ this.label6.Size = new System.Drawing.Size(27, 13);
+ this.label6.TabIndex = 13;
+ this.label6.Text = "Max";
+ //
+ // THR_MIN
+ //
+ this.THR_MIN.Location = new System.Drawing.Point(111, 36);
+ this.THR_MIN.Name = "THR_MIN";
+ this.THR_MIN.Size = new System.Drawing.Size(78, 20);
+ this.THR_MIN.TabIndex = 7;
+ //
+ // label7
+ //
+ this.label7.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label7.Location = new System.Drawing.Point(6, 40);
+ this.label7.Name = "label7";
+ this.label7.Size = new System.Drawing.Size(24, 13);
+ this.label7.TabIndex = 14;
+ this.label7.Text = "Min";
+ //
+ // TRIM_THROTTLE
+ //
+ this.TRIM_THROTTLE.Location = new System.Drawing.Point(111, 13);
+ this.TRIM_THROTTLE.Name = "TRIM_THROTTLE";
+ this.TRIM_THROTTLE.Size = new System.Drawing.Size(78, 20);
+ this.TRIM_THROTTLE.TabIndex = 5;
+ //
+ // label8
+ //
+ this.label8.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label8.Location = new System.Drawing.Point(6, 17);
+ this.label8.Name = "label8";
+ this.label8.Size = new System.Drawing.Size(36, 13);
+ this.label8.TabIndex = 15;
+ this.label8.Text = "Cruise";
+ //
+ // groupBox1
+ //
+ this.groupBox1.Controls.Add(this.ARSPD_RATIO);
+ this.groupBox1.Controls.Add(this.label1);
+ this.groupBox1.Controls.Add(this.ARSPD_FBW_MAX);
+ this.groupBox1.Controls.Add(this.label2);
+ this.groupBox1.Controls.Add(this.ARSPD_FBW_MIN);
+ this.groupBox1.Controls.Add(this.label3);
+ this.groupBox1.Controls.Add(this.TRIM_ARSPD_CM);
+ this.groupBox1.Controls.Add(this.label4);
+ this.groupBox1.Location = new System.Drawing.Point(414, 339);
+ this.groupBox1.Name = "groupBox1";
+ this.groupBox1.Size = new System.Drawing.Size(195, 108);
+ this.groupBox1.TabIndex = 13;
+ this.groupBox1.TabStop = false;
+ this.groupBox1.Text = "Airspeed m/s";
+ //
+ // ARSPD_RATIO
+ //
+ this.ARSPD_RATIO.Location = new System.Drawing.Point(111, 82);
+ this.ARSPD_RATIO.Name = "ARSPD_RATIO";
+ this.ARSPD_RATIO.Size = new System.Drawing.Size(78, 20);
+ this.ARSPD_RATIO.TabIndex = 0;
+ //
+ // label1
+ //
+ this.label1.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label1.Location = new System.Drawing.Point(6, 87);
+ this.label1.Name = "label1";
+ this.label1.Size = new System.Drawing.Size(32, 13);
+ this.label1.TabIndex = 1;
+ this.label1.Text = "Ratio";
+ //
+ // ARSPD_FBW_MAX
+ //
+ this.ARSPD_FBW_MAX.Location = new System.Drawing.Point(111, 59);
+ this.ARSPD_FBW_MAX.Name = "ARSPD_FBW_MAX";
+ this.ARSPD_FBW_MAX.Size = new System.Drawing.Size(78, 20);
+ this.ARSPD_FBW_MAX.TabIndex = 2;
+ //
+ // label2
+ //
+ this.label2.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label2.Location = new System.Drawing.Point(6, 59);
+ this.label2.Name = "label2";
+ this.label2.Size = new System.Drawing.Size(53, 13);
+ this.label2.TabIndex = 3;
+ this.label2.Text = "FBW max";
+ //
+ // ARSPD_FBW_MIN
+ //
+ this.ARSPD_FBW_MIN.Location = new System.Drawing.Point(111, 36);
+ this.ARSPD_FBW_MIN.Name = "ARSPD_FBW_MIN";
+ this.ARSPD_FBW_MIN.Size = new System.Drawing.Size(78, 20);
+ this.ARSPD_FBW_MIN.TabIndex = 4;
+ //
+ // label3
+ //
+ this.label3.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label3.Location = new System.Drawing.Point(6, 40);
+ this.label3.Name = "label3";
+ this.label3.Size = new System.Drawing.Size(50, 13);
+ this.label3.TabIndex = 5;
+ this.label3.Text = "FBW min";
+ //
+ // TRIM_ARSPD_CM
+ //
+ this.TRIM_ARSPD_CM.Location = new System.Drawing.Point(111, 13);
+ this.TRIM_ARSPD_CM.Name = "TRIM_ARSPD_CM";
+ this.TRIM_ARSPD_CM.Size = new System.Drawing.Size(78, 20);
+ this.TRIM_ARSPD_CM.TabIndex = 5;
+ //
+ // label4
+ //
+ this.label4.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label4.Location = new System.Drawing.Point(6, 17);
+ this.label4.Name = "label4";
+ this.label4.Size = new System.Drawing.Size(64, 13);
+ this.label4.TabIndex = 6;
+ this.label4.Text = "Cruise";
+ //
+ // groupBox2
+ //
+ this.groupBox2.Controls.Add(this.LIM_PITCH_MIN);
+ this.groupBox2.Controls.Add(this.label39);
+ this.groupBox2.Controls.Add(this.LIM_PITCH_MAX);
+ this.groupBox2.Controls.Add(this.label38);
+ this.groupBox2.Controls.Add(this.LIM_ROLL_CD);
+ this.groupBox2.Controls.Add(this.label37);
+ this.groupBox2.Location = new System.Drawing.Point(213, 339);
+ this.groupBox2.Name = "groupBox2";
+ this.groupBox2.Size = new System.Drawing.Size(195, 108);
+ this.groupBox2.TabIndex = 14;
+ this.groupBox2.TabStop = false;
+ this.groupBox2.Text = "Navigation Angles";
+ //
+ // LIM_PITCH_MIN
+ //
+ this.LIM_PITCH_MIN.Location = new System.Drawing.Point(111, 59);
+ this.LIM_PITCH_MIN.Name = "LIM_PITCH_MIN";
+ this.LIM_PITCH_MIN.Size = new System.Drawing.Size(78, 20);
+ this.LIM_PITCH_MIN.TabIndex = 9;
+ //
+ // label39
+ //
+ this.label39.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label39.Location = new System.Drawing.Point(6, 63);
+ this.label39.Name = "label39";
+ this.label39.Size = new System.Drawing.Size(51, 13);
+ this.label39.TabIndex = 10;
+ this.label39.Text = "Pitch Min";
+ //
+ // LIM_PITCH_MAX
+ //
+ this.LIM_PITCH_MAX.Location = new System.Drawing.Point(111, 36);
+ this.LIM_PITCH_MAX.Name = "LIM_PITCH_MAX";
+ this.LIM_PITCH_MAX.Size = new System.Drawing.Size(78, 20);
+ this.LIM_PITCH_MAX.TabIndex = 7;
+ //
+ // label38
+ //
+ this.label38.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label38.Location = new System.Drawing.Point(6, 40);
+ this.label38.Name = "label38";
+ this.label38.Size = new System.Drawing.Size(54, 13);
+ this.label38.TabIndex = 11;
+ this.label38.Text = "Pitch Max";
+ //
+ // LIM_ROLL_CD
+ //
+ this.LIM_ROLL_CD.Location = new System.Drawing.Point(111, 13);
+ this.LIM_ROLL_CD.Name = "LIM_ROLL_CD";
+ this.LIM_ROLL_CD.Size = new System.Drawing.Size(78, 20);
+ this.LIM_ROLL_CD.TabIndex = 5;
+ //
+ // label37
+ //
+ this.label37.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label37.Location = new System.Drawing.Point(6, 17);
+ this.label37.Name = "label37";
+ this.label37.Size = new System.Drawing.Size(55, 13);
+ this.label37.TabIndex = 12;
+ this.label37.Text = "Bank Max";
+ //
+ // groupBox15
+ //
+ this.groupBox15.Controls.Add(this.XTRK_ANGLE_CD);
+ this.groupBox15.Controls.Add(this.label79);
+ this.groupBox15.Controls.Add(this.XTRK_GAIN_SC);
+ this.groupBox15.Controls.Add(this.label80);
+ this.groupBox15.Location = new System.Drawing.Point(12, 339);
+ this.groupBox15.Name = "groupBox15";
+ this.groupBox15.Size = new System.Drawing.Size(195, 108);
+ this.groupBox15.TabIndex = 15;
+ this.groupBox15.TabStop = false;
+ this.groupBox15.Text = "Xtrack Pids";
+ //
+ // XTRK_ANGLE_CD
+ //
+ this.XTRK_ANGLE_CD.Location = new System.Drawing.Point(111, 36);
+ this.XTRK_ANGLE_CD.Name = "XTRK_ANGLE_CD";
+ this.XTRK_ANGLE_CD.Size = new System.Drawing.Size(78, 20);
+ this.XTRK_ANGLE_CD.TabIndex = 7;
+ //
+ // label79
+ //
+ this.label79.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label79.Location = new System.Drawing.Point(6, 40);
+ this.label79.Name = "label79";
+ this.label79.Size = new System.Drawing.Size(61, 13);
+ this.label79.TabIndex = 8;
+ this.label79.Text = "Entry Angle";
+ //
+ // XTRK_GAIN_SC
+ //
+ this.XTRK_GAIN_SC.Location = new System.Drawing.Point(111, 13);
+ this.XTRK_GAIN_SC.Name = "XTRK_GAIN_SC";
+ this.XTRK_GAIN_SC.Size = new System.Drawing.Size(78, 20);
+ this.XTRK_GAIN_SC.TabIndex = 5;
+ //
+ // label80
+ //
+ this.label80.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label80.Location = new System.Drawing.Point(6, 17);
+ this.label80.Name = "label80";
+ this.label80.Size = new System.Drawing.Size(52, 13);
+ this.label80.TabIndex = 9;
+ this.label80.Text = "Gain (cm)";
+ //
+ // groupBox16
+ //
+ this.groupBox16.Controls.Add(this.KFF_PTCH2THR);
+ this.groupBox16.Controls.Add(this.label83);
+ this.groupBox16.Controls.Add(this.KFF_RDDRMIX);
+ this.groupBox16.Controls.Add(this.label78);
+ this.groupBox16.Controls.Add(this.KFF_PTCHCOMP);
+ this.groupBox16.Controls.Add(this.label81);
+ this.groupBox16.Location = new System.Drawing.Point(213, 231);
+ this.groupBox16.Name = "groupBox16";
+ this.groupBox16.Size = new System.Drawing.Size(195, 108);
+ this.groupBox16.TabIndex = 16;
+ this.groupBox16.TabStop = false;
+ this.groupBox16.Text = "Other Mix\'s";
+ //
+ // KFF_PTCH2THR
+ //
+ this.KFF_PTCH2THR.Location = new System.Drawing.Point(111, 13);
+ this.KFF_PTCH2THR.Name = "KFF_PTCH2THR";
+ this.KFF_PTCH2THR.Size = new System.Drawing.Size(78, 20);
+ this.KFF_PTCH2THR.TabIndex = 13;
+ //
+ // label83
+ //
+ this.label83.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label83.Location = new System.Drawing.Point(6, 17);
+ this.label83.Name = "label83";
+ this.label83.Size = new System.Drawing.Size(36, 13);
+ this.label83.TabIndex = 14;
+ this.label83.Text = "P to T";
+ //
+ // KFF_RDDRMIX
+ //
+ this.KFF_RDDRMIX.Location = new System.Drawing.Point(111, 59);
+ this.KFF_RDDRMIX.Name = "KFF_RDDRMIX";
+ this.KFF_RDDRMIX.Size = new System.Drawing.Size(78, 20);
+ this.KFF_RDDRMIX.TabIndex = 9;
+ //
+ // label78
+ //
+ this.label78.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label78.Location = new System.Drawing.Point(6, 63);
+ this.label78.Name = "label78";
+ this.label78.Size = new System.Drawing.Size(61, 13);
+ this.label78.TabIndex = 15;
+ this.label78.Text = "Rudder Mix";
+ //
+ // KFF_PTCHCOMP
+ //
+ this.KFF_PTCHCOMP.Location = new System.Drawing.Point(111, 36);
+ this.KFF_PTCHCOMP.Name = "KFF_PTCHCOMP";
+ this.KFF_PTCHCOMP.Size = new System.Drawing.Size(78, 20);
+ this.KFF_PTCHCOMP.TabIndex = 7;
+ //
+ // label81
+ //
+ this.label81.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label81.Location = new System.Drawing.Point(6, 40);
+ this.label81.Name = "label81";
+ this.label81.Size = new System.Drawing.Size(61, 13);
+ this.label81.TabIndex = 16;
+ this.label81.Text = "Pitch Comp";
+ //
+ // groupBox14
+ //
+ this.groupBox14.Controls.Add(this.ENRGY2THR_IMAX);
+ this.groupBox14.Controls.Add(this.label73);
+ this.groupBox14.Controls.Add(this.ENRGY2THR_D);
+ this.groupBox14.Controls.Add(this.label74);
+ this.groupBox14.Controls.Add(this.ENRGY2THR_I);
+ this.groupBox14.Controls.Add(this.label75);
+ this.groupBox14.Controls.Add(this.ENRGY2THR_P);
+ this.groupBox14.Controls.Add(this.label76);
+ this.groupBox14.Location = new System.Drawing.Point(12, 231);
+ this.groupBox14.Name = "groupBox14";
+ this.groupBox14.Size = new System.Drawing.Size(195, 108);
+ this.groupBox14.TabIndex = 17;
+ this.groupBox14.TabStop = false;
+ this.groupBox14.Text = "Energy/Alt Pid";
+ //
+ // ENRGY2THR_IMAX
+ //
+ this.ENRGY2THR_IMAX.Location = new System.Drawing.Point(111, 82);
+ this.ENRGY2THR_IMAX.Name = "ENRGY2THR_IMAX";
+ this.ENRGY2THR_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.ENRGY2THR_IMAX.TabIndex = 11;
+ //
+ // label73
+ //
+ this.label73.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label73.Location = new System.Drawing.Point(6, 86);
+ this.label73.Name = "label73";
+ this.label73.Size = new System.Drawing.Size(54, 13);
+ this.label73.TabIndex = 12;
+ this.label73.Text = "INT_MAX";
+ //
+ // ENRGY2THR_D
+ //
+ this.ENRGY2THR_D.Location = new System.Drawing.Point(111, 59);
+ this.ENRGY2THR_D.Name = "ENRGY2THR_D";
+ this.ENRGY2THR_D.Size = new System.Drawing.Size(78, 20);
+ this.ENRGY2THR_D.TabIndex = 9;
+ //
+ // label74
+ //
+ this.label74.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label74.Location = new System.Drawing.Point(6, 63);
+ this.label74.Name = "label74";
+ this.label74.Size = new System.Drawing.Size(15, 13);
+ this.label74.TabIndex = 13;
+ this.label74.Text = "D";
+ //
+ // ENRGY2THR_I
+ //
+ this.ENRGY2THR_I.Location = new System.Drawing.Point(111, 36);
+ this.ENRGY2THR_I.Name = "ENRGY2THR_I";
+ this.ENRGY2THR_I.Size = new System.Drawing.Size(78, 20);
+ this.ENRGY2THR_I.TabIndex = 7;
+ //
+ // label75
+ //
+ this.label75.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label75.Location = new System.Drawing.Point(6, 40);
+ this.label75.Name = "label75";
+ this.label75.Size = new System.Drawing.Size(10, 13);
+ this.label75.TabIndex = 14;
+ this.label75.Text = "I";
+ //
+ // ENRGY2THR_P
+ //
+ this.ENRGY2THR_P.Location = new System.Drawing.Point(111, 13);
+ this.ENRGY2THR_P.Name = "ENRGY2THR_P";
+ this.ENRGY2THR_P.Size = new System.Drawing.Size(78, 20);
+ this.ENRGY2THR_P.TabIndex = 5;
+ //
+ // label76
+ //
+ this.label76.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label76.Location = new System.Drawing.Point(6, 17);
+ this.label76.Name = "label76";
+ this.label76.Size = new System.Drawing.Size(14, 13);
+ this.label76.TabIndex = 15;
+ this.label76.Text = "P";
+ //
+ // groupBox13
+ //
+ this.groupBox13.Controls.Add(this.ALT2PTCH_IMAX);
+ this.groupBox13.Controls.Add(this.label69);
+ this.groupBox13.Controls.Add(this.ALT2PTCH_D);
+ this.groupBox13.Controls.Add(this.label70);
+ this.groupBox13.Controls.Add(this.ALT2PTCH_I);
+ this.groupBox13.Controls.Add(this.label71);
+ this.groupBox13.Controls.Add(this.ALT2PTCH_P);
+ this.groupBox13.Controls.Add(this.label72);
+ this.groupBox13.Location = new System.Drawing.Point(414, 123);
+ this.groupBox13.Name = "groupBox13";
+ this.groupBox13.Size = new System.Drawing.Size(195, 108);
+ this.groupBox13.TabIndex = 18;
+ this.groupBox13.TabStop = false;
+ this.groupBox13.Text = "Nav Pitch Alt Pid";
+ //
+ // ALT2PTCH_IMAX
+ //
+ this.ALT2PTCH_IMAX.Location = new System.Drawing.Point(111, 82);
+ this.ALT2PTCH_IMAX.Name = "ALT2PTCH_IMAX";
+ this.ALT2PTCH_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.ALT2PTCH_IMAX.TabIndex = 0;
+ //
+ // label69
+ //
+ this.label69.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label69.Location = new System.Drawing.Point(6, 86);
+ this.label69.Name = "label69";
+ this.label69.Size = new System.Drawing.Size(54, 13);
+ this.label69.TabIndex = 1;
+ this.label69.Text = "INT_MAX";
+ //
+ // ALT2PTCH_D
+ //
+ this.ALT2PTCH_D.Location = new System.Drawing.Point(111, 59);
+ this.ALT2PTCH_D.Name = "ALT2PTCH_D";
+ this.ALT2PTCH_D.Size = new System.Drawing.Size(78, 20);
+ this.ALT2PTCH_D.TabIndex = 2;
+ //
+ // label70
+ //
+ this.label70.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label70.Location = new System.Drawing.Point(6, 63);
+ this.label70.Name = "label70";
+ this.label70.Size = new System.Drawing.Size(15, 13);
+ this.label70.TabIndex = 3;
+ this.label70.Text = "D";
+ //
+ // ALT2PTCH_I
+ //
+ this.ALT2PTCH_I.Location = new System.Drawing.Point(111, 36);
+ this.ALT2PTCH_I.Name = "ALT2PTCH_I";
+ this.ALT2PTCH_I.Size = new System.Drawing.Size(78, 20);
+ this.ALT2PTCH_I.TabIndex = 4;
+ //
+ // label71
+ //
+ this.label71.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label71.Location = new System.Drawing.Point(6, 40);
+ this.label71.Name = "label71";
+ this.label71.Size = new System.Drawing.Size(10, 13);
+ this.label71.TabIndex = 5;
+ this.label71.Text = "I";
+ //
+ // ALT2PTCH_P
+ //
+ this.ALT2PTCH_P.Location = new System.Drawing.Point(111, 13);
+ this.ALT2PTCH_P.Name = "ALT2PTCH_P";
+ this.ALT2PTCH_P.Size = new System.Drawing.Size(78, 20);
+ this.ALT2PTCH_P.TabIndex = 6;
+ //
+ // label72
+ //
+ this.label72.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label72.Location = new System.Drawing.Point(6, 17);
+ this.label72.Name = "label72";
+ this.label72.Size = new System.Drawing.Size(14, 13);
+ this.label72.TabIndex = 7;
+ this.label72.Text = "P";
+ //
+ // groupBox12
+ //
+ this.groupBox12.Controls.Add(this.ARSP2PTCH_IMAX);
+ this.groupBox12.Controls.Add(this.label65);
+ this.groupBox12.Controls.Add(this.ARSP2PTCH_D);
+ this.groupBox12.Controls.Add(this.label66);
+ this.groupBox12.Controls.Add(this.ARSP2PTCH_I);
+ this.groupBox12.Controls.Add(this.label67);
+ this.groupBox12.Controls.Add(this.ARSP2PTCH_P);
+ this.groupBox12.Controls.Add(this.label68);
+ this.groupBox12.Location = new System.Drawing.Point(213, 123);
+ this.groupBox12.Name = "groupBox12";
+ this.groupBox12.Size = new System.Drawing.Size(195, 108);
+ this.groupBox12.TabIndex = 19;
+ this.groupBox12.TabStop = false;
+ this.groupBox12.Text = "Nav Pitch AS Pid";
+ //
+ // ARSP2PTCH_IMAX
+ //
+ this.ARSP2PTCH_IMAX.Location = new System.Drawing.Point(111, 82);
+ this.ARSP2PTCH_IMAX.Name = "ARSP2PTCH_IMAX";
+ this.ARSP2PTCH_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.ARSP2PTCH_IMAX.TabIndex = 0;
+ //
+ // label65
+ //
+ this.label65.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label65.Location = new System.Drawing.Point(6, 86);
+ this.label65.Name = "label65";
+ this.label65.Size = new System.Drawing.Size(54, 13);
+ this.label65.TabIndex = 1;
+ this.label65.Text = "INT_MAX";
+ //
+ // ARSP2PTCH_D
+ //
+ this.ARSP2PTCH_D.Location = new System.Drawing.Point(111, 59);
+ this.ARSP2PTCH_D.Name = "ARSP2PTCH_D";
+ this.ARSP2PTCH_D.Size = new System.Drawing.Size(78, 20);
+ this.ARSP2PTCH_D.TabIndex = 2;
+ //
+ // label66
+ //
+ this.label66.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label66.Location = new System.Drawing.Point(6, 63);
+ this.label66.Name = "label66";
+ this.label66.Size = new System.Drawing.Size(15, 13);
+ this.label66.TabIndex = 3;
+ this.label66.Text = "D";
+ //
+ // ARSP2PTCH_I
+ //
+ this.ARSP2PTCH_I.Location = new System.Drawing.Point(111, 36);
+ this.ARSP2PTCH_I.Name = "ARSP2PTCH_I";
+ this.ARSP2PTCH_I.Size = new System.Drawing.Size(78, 20);
+ this.ARSP2PTCH_I.TabIndex = 4;
+ //
+ // label67
+ //
+ this.label67.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label67.Location = new System.Drawing.Point(6, 40);
+ this.label67.Name = "label67";
+ this.label67.Size = new System.Drawing.Size(10, 13);
+ this.label67.TabIndex = 5;
+ this.label67.Text = "I";
+ //
+ // ARSP2PTCH_P
+ //
+ this.ARSP2PTCH_P.Location = new System.Drawing.Point(111, 13);
+ this.ARSP2PTCH_P.Name = "ARSP2PTCH_P";
+ this.ARSP2PTCH_P.Size = new System.Drawing.Size(78, 20);
+ this.ARSP2PTCH_P.TabIndex = 6;
+ //
+ // label68
+ //
+ this.label68.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label68.Location = new System.Drawing.Point(6, 17);
+ this.label68.Name = "label68";
+ this.label68.Size = new System.Drawing.Size(14, 13);
+ this.label68.TabIndex = 7;
+ this.label68.Text = "P";
+ //
+ // groupBox11
+ //
+ this.groupBox11.Controls.Add(this.HDNG2RLL_IMAX);
+ this.groupBox11.Controls.Add(this.label61);
+ this.groupBox11.Controls.Add(this.HDNG2RLL_D);
+ this.groupBox11.Controls.Add(this.label62);
+ this.groupBox11.Controls.Add(this.HDNG2RLL_I);
+ this.groupBox11.Controls.Add(this.label63);
+ this.groupBox11.Controls.Add(this.HDNG2RLL_P);
+ this.groupBox11.Controls.Add(this.label64);
+ this.groupBox11.Location = new System.Drawing.Point(12, 123);
+ this.groupBox11.Name = "groupBox11";
+ this.groupBox11.Size = new System.Drawing.Size(195, 108);
+ this.groupBox11.TabIndex = 20;
+ this.groupBox11.TabStop = false;
+ this.groupBox11.Text = "Nav Roll Pid";
+ //
+ // HDNG2RLL_IMAX
+ //
+ this.HDNG2RLL_IMAX.Location = new System.Drawing.Point(111, 82);
+ this.HDNG2RLL_IMAX.Name = "HDNG2RLL_IMAX";
+ this.HDNG2RLL_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.HDNG2RLL_IMAX.TabIndex = 11;
+ //
+ // label61
+ //
+ this.label61.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label61.Location = new System.Drawing.Point(6, 86);
+ this.label61.Name = "label61";
+ this.label61.Size = new System.Drawing.Size(54, 13);
+ this.label61.TabIndex = 12;
+ this.label61.Text = "INT_MAX";
+ //
+ // HDNG2RLL_D
+ //
+ this.HDNG2RLL_D.Location = new System.Drawing.Point(111, 59);
+ this.HDNG2RLL_D.Name = "HDNG2RLL_D";
+ this.HDNG2RLL_D.Size = new System.Drawing.Size(78, 20);
+ this.HDNG2RLL_D.TabIndex = 9;
+ //
+ // label62
+ //
+ this.label62.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label62.Location = new System.Drawing.Point(6, 63);
+ this.label62.Name = "label62";
+ this.label62.Size = new System.Drawing.Size(15, 13);
+ this.label62.TabIndex = 13;
+ this.label62.Text = "D";
+ //
+ // HDNG2RLL_I
+ //
+ this.HDNG2RLL_I.Location = new System.Drawing.Point(111, 36);
+ this.HDNG2RLL_I.Name = "HDNG2RLL_I";
+ this.HDNG2RLL_I.Size = new System.Drawing.Size(78, 20);
+ this.HDNG2RLL_I.TabIndex = 7;
+ //
+ // label63
+ //
+ this.label63.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label63.Location = new System.Drawing.Point(6, 40);
+ this.label63.Name = "label63";
+ this.label63.Size = new System.Drawing.Size(10, 13);
+ this.label63.TabIndex = 14;
+ this.label63.Text = "I";
+ //
+ // HDNG2RLL_P
+ //
+ this.HDNG2RLL_P.Location = new System.Drawing.Point(111, 13);
+ this.HDNG2RLL_P.Name = "HDNG2RLL_P";
+ this.HDNG2RLL_P.Size = new System.Drawing.Size(78, 20);
+ this.HDNG2RLL_P.TabIndex = 5;
+ //
+ // label64
+ //
+ this.label64.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label64.Location = new System.Drawing.Point(6, 17);
+ this.label64.Name = "label64";
+ this.label64.Size = new System.Drawing.Size(14, 13);
+ this.label64.TabIndex = 15;
+ this.label64.Text = "P";
+ //
+ // groupBox10
+ //
+ this.groupBox10.Controls.Add(this.YW2SRV_IMAX);
+ this.groupBox10.Controls.Add(this.label57);
+ this.groupBox10.Controls.Add(this.YW2SRV_D);
+ this.groupBox10.Controls.Add(this.label58);
+ this.groupBox10.Controls.Add(this.YW2SRV_I);
+ this.groupBox10.Controls.Add(this.label59);
+ this.groupBox10.Controls.Add(this.YW2SRV_P);
+ this.groupBox10.Controls.Add(this.label60);
+ this.groupBox10.Location = new System.Drawing.Point(414, 15);
+ this.groupBox10.Name = "groupBox10";
+ this.groupBox10.Size = new System.Drawing.Size(195, 108);
+ this.groupBox10.TabIndex = 21;
+ this.groupBox10.TabStop = false;
+ this.groupBox10.Text = "Servo Yaw Pid";
+ //
+ // YW2SRV_IMAX
+ //
+ this.YW2SRV_IMAX.Location = new System.Drawing.Point(111, 82);
+ this.YW2SRV_IMAX.Name = "YW2SRV_IMAX";
+ this.YW2SRV_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.YW2SRV_IMAX.TabIndex = 11;
+ //
+ // label57
+ //
+ this.label57.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label57.Location = new System.Drawing.Point(6, 86);
+ this.label57.Name = "label57";
+ this.label57.Size = new System.Drawing.Size(54, 13);
+ this.label57.TabIndex = 12;
+ this.label57.Text = "INT_MAX";
+ //
+ // YW2SRV_D
+ //
+ this.YW2SRV_D.Location = new System.Drawing.Point(111, 59);
+ this.YW2SRV_D.Name = "YW2SRV_D";
+ this.YW2SRV_D.Size = new System.Drawing.Size(78, 20);
+ this.YW2SRV_D.TabIndex = 9;
+ //
+ // label58
+ //
+ this.label58.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label58.Location = new System.Drawing.Point(6, 63);
+ this.label58.Name = "label58";
+ this.label58.Size = new System.Drawing.Size(15, 13);
+ this.label58.TabIndex = 13;
+ this.label58.Text = "D";
+ //
+ // YW2SRV_I
+ //
+ this.YW2SRV_I.Location = new System.Drawing.Point(111, 36);
+ this.YW2SRV_I.Name = "YW2SRV_I";
+ this.YW2SRV_I.Size = new System.Drawing.Size(78, 20);
+ this.YW2SRV_I.TabIndex = 7;
+ //
+ // label59
+ //
+ this.label59.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label59.Location = new System.Drawing.Point(6, 40);
+ this.label59.Name = "label59";
+ this.label59.Size = new System.Drawing.Size(10, 13);
+ this.label59.TabIndex = 14;
+ this.label59.Text = "I";
+ //
+ // YW2SRV_P
+ //
+ this.YW2SRV_P.Location = new System.Drawing.Point(111, 13);
+ this.YW2SRV_P.Name = "YW2SRV_P";
+ this.YW2SRV_P.Size = new System.Drawing.Size(78, 20);
+ this.YW2SRV_P.TabIndex = 5;
+ //
+ // label60
+ //
+ this.label60.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label60.Location = new System.Drawing.Point(6, 17);
+ this.label60.Name = "label60";
+ this.label60.Size = new System.Drawing.Size(14, 13);
+ this.label60.TabIndex = 15;
+ this.label60.Text = "P";
+ //
+ // groupBox9
+ //
+ this.groupBox9.Controls.Add(this.PTCH2SRV_IMAX);
+ this.groupBox9.Controls.Add(this.label53);
+ this.groupBox9.Controls.Add(this.PTCH2SRV_D);
+ this.groupBox9.Controls.Add(this.label54);
+ this.groupBox9.Controls.Add(this.PTCH2SRV_I);
+ this.groupBox9.Controls.Add(this.label55);
+ this.groupBox9.Controls.Add(this.PTCH2SRV_P);
+ this.groupBox9.Controls.Add(this.label56);
+ this.groupBox9.Location = new System.Drawing.Point(213, 15);
+ this.groupBox9.Name = "groupBox9";
+ this.groupBox9.Size = new System.Drawing.Size(195, 108);
+ this.groupBox9.TabIndex = 22;
+ this.groupBox9.TabStop = false;
+ this.groupBox9.Text = "Servo Pitch Pid";
+ //
+ // PTCH2SRV_IMAX
+ //
+ this.PTCH2SRV_IMAX.Location = new System.Drawing.Point(111, 82);
+ this.PTCH2SRV_IMAX.Name = "PTCH2SRV_IMAX";
+ this.PTCH2SRV_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.PTCH2SRV_IMAX.TabIndex = 11;
+ //
+ // label53
+ //
+ this.label53.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label53.Location = new System.Drawing.Point(6, 86);
+ this.label53.Name = "label53";
+ this.label53.Size = new System.Drawing.Size(54, 13);
+ this.label53.TabIndex = 12;
+ this.label53.Text = "INT_MAX";
+ //
+ // PTCH2SRV_D
+ //
+ this.PTCH2SRV_D.Location = new System.Drawing.Point(111, 59);
+ this.PTCH2SRV_D.Name = "PTCH2SRV_D";
+ this.PTCH2SRV_D.Size = new System.Drawing.Size(78, 20);
+ this.PTCH2SRV_D.TabIndex = 9;
+ //
+ // label54
+ //
+ this.label54.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label54.Location = new System.Drawing.Point(6, 63);
+ this.label54.Name = "label54";
+ this.label54.Size = new System.Drawing.Size(15, 13);
+ this.label54.TabIndex = 13;
+ this.label54.Text = "D";
+ //
+ // PTCH2SRV_I
+ //
+ this.PTCH2SRV_I.Location = new System.Drawing.Point(111, 36);
+ this.PTCH2SRV_I.Name = "PTCH2SRV_I";
+ this.PTCH2SRV_I.Size = new System.Drawing.Size(78, 20);
+ this.PTCH2SRV_I.TabIndex = 7;
+ //
+ // label55
+ //
+ this.label55.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label55.Location = new System.Drawing.Point(6, 40);
+ this.label55.Name = "label55";
+ this.label55.Size = new System.Drawing.Size(10, 13);
+ this.label55.TabIndex = 14;
+ this.label55.Text = "I";
+ //
+ // PTCH2SRV_P
+ //
+ this.PTCH2SRV_P.Location = new System.Drawing.Point(111, 13);
+ this.PTCH2SRV_P.Name = "PTCH2SRV_P";
+ this.PTCH2SRV_P.Size = new System.Drawing.Size(78, 20);
+ this.PTCH2SRV_P.TabIndex = 5;
+ //
+ // label56
+ //
+ this.label56.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label56.Location = new System.Drawing.Point(6, 17);
+ this.label56.Name = "label56";
+ this.label56.Size = new System.Drawing.Size(14, 13);
+ this.label56.TabIndex = 15;
+ this.label56.Text = "P";
+ //
+ // groupBox8
+ //
+ this.groupBox8.Controls.Add(this.RLL2SRV_IMAX);
+ this.groupBox8.Controls.Add(this.label49);
+ this.groupBox8.Controls.Add(this.RLL2SRV_D);
+ this.groupBox8.Controls.Add(this.label50);
+ this.groupBox8.Controls.Add(this.RLL2SRV_I);
+ this.groupBox8.Controls.Add(this.label51);
+ this.groupBox8.Controls.Add(this.RLL2SRV_P);
+ this.groupBox8.Controls.Add(this.label52);
+ this.groupBox8.Location = new System.Drawing.Point(12, 15);
+ this.groupBox8.Name = "groupBox8";
+ this.groupBox8.Size = new System.Drawing.Size(195, 108);
+ this.groupBox8.TabIndex = 23;
+ this.groupBox8.TabStop = false;
+ this.groupBox8.Text = "Servo Roll Pid";
+ //
+ // RLL2SRV_IMAX
+ //
+ this.RLL2SRV_IMAX.Location = new System.Drawing.Point(111, 82);
+ this.RLL2SRV_IMAX.Name = "RLL2SRV_IMAX";
+ this.RLL2SRV_IMAX.Size = new System.Drawing.Size(78, 20);
+ this.RLL2SRV_IMAX.TabIndex = 11;
+ //
+ // label49
+ //
+ this.label49.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label49.Location = new System.Drawing.Point(6, 86);
+ this.label49.Name = "label49";
+ this.label49.Size = new System.Drawing.Size(54, 13);
+ this.label49.TabIndex = 12;
+ this.label49.Text = "INT_MAX";
+ //
+ // RLL2SRV_D
+ //
+ this.RLL2SRV_D.Location = new System.Drawing.Point(111, 59);
+ this.RLL2SRV_D.Name = "RLL2SRV_D";
+ this.RLL2SRV_D.Size = new System.Drawing.Size(78, 20);
+ this.RLL2SRV_D.TabIndex = 9;
+ //
+ // label50
+ //
+ this.label50.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label50.Location = new System.Drawing.Point(6, 63);
+ this.label50.Name = "label50";
+ this.label50.Size = new System.Drawing.Size(15, 13);
+ this.label50.TabIndex = 13;
+ this.label50.Text = "D";
+ //
+ // RLL2SRV_I
+ //
+ this.RLL2SRV_I.Location = new System.Drawing.Point(111, 36);
+ this.RLL2SRV_I.Name = "RLL2SRV_I";
+ this.RLL2SRV_I.Size = new System.Drawing.Size(78, 20);
+ this.RLL2SRV_I.TabIndex = 7;
+ //
+ // label51
+ //
+ this.label51.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label51.Location = new System.Drawing.Point(6, 40);
+ this.label51.Name = "label51";
+ this.label51.Size = new System.Drawing.Size(10, 13);
+ this.label51.TabIndex = 14;
+ this.label51.Text = "I";
+ //
+ // RLL2SRV_P
+ //
+ this.RLL2SRV_P.Location = new System.Drawing.Point(111, 13);
+ this.RLL2SRV_P.Name = "RLL2SRV_P";
+ this.RLL2SRV_P.Size = new System.Drawing.Size(78, 20);
+ this.RLL2SRV_P.TabIndex = 5;
+ //
+ // label52
+ //
+ this.label52.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label52.Location = new System.Drawing.Point(6, 17);
+ this.label52.Name = "label52";
+ this.label52.Size = new System.Drawing.Size(14, 13);
+ this.label52.TabIndex = 15;
+ this.label52.Text = "P";
+ //
+ // ConfigArduplane
+ //
+ this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+ this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+ this.Controls.Add(this.groupBox3);
+ this.Controls.Add(this.groupBox1);
+ this.Controls.Add(this.groupBox2);
+ this.Controls.Add(this.groupBox15);
+ this.Controls.Add(this.groupBox16);
+ this.Controls.Add(this.groupBox14);
+ this.Controls.Add(this.groupBox13);
+ this.Controls.Add(this.groupBox12);
+ this.Controls.Add(this.groupBox11);
+ this.Controls.Add(this.groupBox10);
+ this.Controls.Add(this.groupBox9);
+ this.Controls.Add(this.groupBox8);
+ this.Name = "ConfigArduplane";
+ this.Size = new System.Drawing.Size(621, 456);
+ this.groupBox3.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.THR_FS_VALUE)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_MAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.THR_MIN)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.TRIM_THROTTLE)).EndInit();
+ this.groupBox1.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.ARSPD_RATIO)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MIN)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.TRIM_ARSPD_CM)).EndInit();
+ this.groupBox2.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MIN)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.LIM_ROLL_CD)).EndInit();
+ this.groupBox15.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC)).EndInit();
+ this.groupBox16.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCH2THR)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.KFF_RDDRMIX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCHCOMP)).EndInit();
+ this.groupBox14.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_P)).EndInit();
+ this.groupBox13.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_P)).EndInit();
+ this.groupBox12.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_P)).EndInit();
+ this.groupBox11.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_P)).EndInit();
+ this.groupBox10.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_P)).EndInit();
+ this.groupBox9.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_P)).EndInit();
+ this.groupBox8.ResumeLayout(false);
+ ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_IMAX)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_D)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_I)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).EndInit();
+ this.ResumeLayout(false);
+
+ }
+
+ #endregion
+
+ private System.Windows.Forms.GroupBox groupBox3;
+ private System.Windows.Forms.NumericUpDown THR_FS_VALUE;
+ private System.Windows.Forms.Label label5;
+ private System.Windows.Forms.NumericUpDown THR_MAX;
+ private System.Windows.Forms.Label label6;
+ private System.Windows.Forms.NumericUpDown THR_MIN;
+ private System.Windows.Forms.Label label7;
+ private System.Windows.Forms.NumericUpDown TRIM_THROTTLE;
+ private System.Windows.Forms.Label label8;
+ private System.Windows.Forms.GroupBox groupBox1;
+ private System.Windows.Forms.NumericUpDown ARSPD_RATIO;
+ private System.Windows.Forms.Label label1;
+ private System.Windows.Forms.NumericUpDown ARSPD_FBW_MAX;
+ private System.Windows.Forms.Label label2;
+ private System.Windows.Forms.NumericUpDown ARSPD_FBW_MIN;
+ private System.Windows.Forms.Label label3;
+ private System.Windows.Forms.NumericUpDown TRIM_ARSPD_CM;
+ private System.Windows.Forms.Label label4;
+ private System.Windows.Forms.GroupBox groupBox2;
+ private System.Windows.Forms.NumericUpDown LIM_PITCH_MIN;
+ private System.Windows.Forms.Label label39;
+ private System.Windows.Forms.NumericUpDown LIM_PITCH_MAX;
+ private System.Windows.Forms.Label label38;
+ private System.Windows.Forms.NumericUpDown LIM_ROLL_CD;
+ private System.Windows.Forms.Label label37;
+ private System.Windows.Forms.GroupBox groupBox15;
+ private System.Windows.Forms.NumericUpDown XTRK_ANGLE_CD;
+ private System.Windows.Forms.Label label79;
+ private System.Windows.Forms.NumericUpDown XTRK_GAIN_SC;
+ private System.Windows.Forms.Label label80;
+ private System.Windows.Forms.GroupBox groupBox16;
+ private System.Windows.Forms.NumericUpDown KFF_PTCH2THR;
+ private System.Windows.Forms.Label label83;
+ private System.Windows.Forms.NumericUpDown KFF_RDDRMIX;
+ private System.Windows.Forms.Label label78;
+ private System.Windows.Forms.NumericUpDown KFF_PTCHCOMP;
+ private System.Windows.Forms.Label label81;
+ private System.Windows.Forms.GroupBox groupBox14;
+ private System.Windows.Forms.NumericUpDown ENRGY2THR_IMAX;
+ private System.Windows.Forms.Label label73;
+ private System.Windows.Forms.NumericUpDown ENRGY2THR_D;
+ private System.Windows.Forms.Label label74;
+ private System.Windows.Forms.NumericUpDown ENRGY2THR_I;
+ private System.Windows.Forms.Label label75;
+ private System.Windows.Forms.NumericUpDown ENRGY2THR_P;
+ private System.Windows.Forms.Label label76;
+ private System.Windows.Forms.GroupBox groupBox13;
+ private System.Windows.Forms.NumericUpDown ALT2PTCH_IMAX;
+ private System.Windows.Forms.Label label69;
+ private System.Windows.Forms.NumericUpDown ALT2PTCH_D;
+ private System.Windows.Forms.Label label70;
+ private System.Windows.Forms.NumericUpDown ALT2PTCH_I;
+ private System.Windows.Forms.Label label71;
+ private System.Windows.Forms.NumericUpDown ALT2PTCH_P;
+ private System.Windows.Forms.Label label72;
+ private System.Windows.Forms.GroupBox groupBox12;
+ private System.Windows.Forms.NumericUpDown ARSP2PTCH_IMAX;
+ private System.Windows.Forms.Label label65;
+ private System.Windows.Forms.NumericUpDown ARSP2PTCH_D;
+ private System.Windows.Forms.Label label66;
+ private System.Windows.Forms.NumericUpDown ARSP2PTCH_I;
+ private System.Windows.Forms.Label label67;
+ private System.Windows.Forms.NumericUpDown ARSP2PTCH_P;
+ private System.Windows.Forms.Label label68;
+ private System.Windows.Forms.GroupBox groupBox11;
+ private System.Windows.Forms.NumericUpDown HDNG2RLL_IMAX;
+ private System.Windows.Forms.Label label61;
+ private System.Windows.Forms.NumericUpDown HDNG2RLL_D;
+ private System.Windows.Forms.Label label62;
+ private System.Windows.Forms.NumericUpDown HDNG2RLL_I;
+ private System.Windows.Forms.Label label63;
+ private System.Windows.Forms.NumericUpDown HDNG2RLL_P;
+ private System.Windows.Forms.Label label64;
+ private System.Windows.Forms.GroupBox groupBox10;
+ private System.Windows.Forms.NumericUpDown YW2SRV_IMAX;
+ private System.Windows.Forms.Label label57;
+ private System.Windows.Forms.NumericUpDown YW2SRV_D;
+ private System.Windows.Forms.Label label58;
+ private System.Windows.Forms.NumericUpDown YW2SRV_I;
+ private System.Windows.Forms.Label label59;
+ private System.Windows.Forms.NumericUpDown YW2SRV_P;
+ private System.Windows.Forms.Label label60;
+ private System.Windows.Forms.GroupBox groupBox9;
+ private System.Windows.Forms.NumericUpDown PTCH2SRV_IMAX;
+ private System.Windows.Forms.Label label53;
+ private System.Windows.Forms.NumericUpDown PTCH2SRV_D;
+ private System.Windows.Forms.Label label54;
+ private System.Windows.Forms.NumericUpDown PTCH2SRV_I;
+ private System.Windows.Forms.Label label55;
+ private System.Windows.Forms.NumericUpDown PTCH2SRV_P;
+ private System.Windows.Forms.Label label56;
+ private System.Windows.Forms.GroupBox groupBox8;
+ private System.Windows.Forms.NumericUpDown RLL2SRV_IMAX;
+ private System.Windows.Forms.Label label49;
+ private System.Windows.Forms.NumericUpDown RLL2SRV_D;
+ private System.Windows.Forms.Label label50;
+ private System.Windows.Forms.NumericUpDown RLL2SRV_I;
+ private System.Windows.Forms.Label label51;
+ private System.Windows.Forms.NumericUpDown RLL2SRV_P;
+ private System.Windows.Forms.Label label52;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs
new file mode 100644
index 0000000000..8a4ac7a73b
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs
@@ -0,0 +1,19 @@
+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.GCSViews.ConfigurationView
+{
+ public partial class ConfigArduplane : UserControl
+ {
+ public ConfigArduplane()
+ {
+ InitializeComponent();
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.resx
new file mode 100644
index 0000000000..7080a7d118
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.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/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs
new file mode 100644
index 0000000000..2681862081
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs
@@ -0,0 +1,300 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class ConfigBatteryMonitoring
+ {
+ ///
+ /// 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()
+ {
+ System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigBatteryMonitoring));
+ this.groupBox4 = new System.Windows.Forms.GroupBox();
+ this.label31 = new System.Windows.Forms.Label();
+ this.label32 = new System.Windows.Forms.Label();
+ this.label33 = new System.Windows.Forms.Label();
+ this.TXT_ampspervolt = new System.Windows.Forms.TextBox();
+ this.label34 = new System.Windows.Forms.Label();
+ this.TXT_divider = new System.Windows.Forms.TextBox();
+ this.label35 = new System.Windows.Forms.Label();
+ this.TXT_voltage = new System.Windows.Forms.TextBox();
+ this.TXT_inputvoltage = new System.Windows.Forms.TextBox();
+ this.TXT_measuredvoltage = new System.Windows.Forms.TextBox();
+ this.label47 = new System.Windows.Forms.Label();
+ this.CMB_batmonsensortype = new System.Windows.Forms.ComboBox();
+ this.textBox3 = new System.Windows.Forms.TextBox();
+ this.label29 = new System.Windows.Forms.Label();
+ this.label30 = new System.Windows.Forms.Label();
+ this.TXT_battcapacity = new System.Windows.Forms.TextBox();
+ this.CMB_batmontype = new System.Windows.Forms.ComboBox();
+ this.pictureBox5 = new System.Windows.Forms.PictureBox();
+ this.groupBox4.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).BeginInit();
+ this.SuspendLayout();
+ //
+ // groupBox4
+ //
+ this.groupBox4.Controls.Add(this.label31);
+ this.groupBox4.Controls.Add(this.label32);
+ this.groupBox4.Controls.Add(this.label33);
+ this.groupBox4.Controls.Add(this.TXT_ampspervolt);
+ this.groupBox4.Controls.Add(this.label34);
+ this.groupBox4.Controls.Add(this.TXT_divider);
+ this.groupBox4.Controls.Add(this.label35);
+ this.groupBox4.Controls.Add(this.TXT_voltage);
+ this.groupBox4.Controls.Add(this.TXT_inputvoltage);
+ this.groupBox4.Controls.Add(this.TXT_measuredvoltage);
+ this.groupBox4.Location = new System.Drawing.Point(14, 172);
+ this.groupBox4.Name = "groupBox4";
+ this.groupBox4.Size = new System.Drawing.Size(238, 131);
+ this.groupBox4.TabIndex = 50;
+ this.groupBox4.TabStop = false;
+ this.groupBox4.Text = "Calibration";
+ //
+ // label31
+ //
+ this.label31.AutoSize = true;
+ this.label31.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label31.Location = new System.Drawing.Point(5, 16);
+ this.label31.Margin = new System.Windows.Forms.Padding(2, 0, 2, 0);
+ this.label31.Name = "label31";
+ this.label31.Size = new System.Drawing.Size(110, 13);
+ this.label31.TabIndex = 29;
+ this.label31.Text = "1. APM Input voltage:";
+ //
+ // label32
+ //
+ this.label32.AutoSize = true;
+ this.label32.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label32.Location = new System.Drawing.Point(5, 38);
+ this.label32.Margin = new System.Windows.Forms.Padding(2, 0, 2, 0);
+ this.label32.Name = "label32";
+ this.label32.Size = new System.Drawing.Size(142, 13);
+ this.label32.TabIndex = 30;
+ this.label32.Text = "2. Measured battery voltage:";
+ //
+ // label33
+ //
+ this.label33.AutoSize = true;
+ this.label33.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label33.Location = new System.Drawing.Point(5, 60);
+ this.label33.Margin = new System.Windows.Forms.Padding(2, 0, 2, 0);
+ this.label33.Name = "label33";
+ this.label33.Size = new System.Drawing.Size(135, 13);
+ this.label33.TabIndex = 31;
+ this.label33.Text = "3. Battery voltage (Calced):";
+ //
+ // TXT_ampspervolt
+ //
+ this.TXT_ampspervolt.Location = new System.Drawing.Point(149, 100);
+ this.TXT_ampspervolt.Margin = new System.Windows.Forms.Padding(2);
+ this.TXT_ampspervolt.Name = "TXT_ampspervolt";
+ this.TXT_ampspervolt.Size = new System.Drawing.Size(76, 20);
+ this.TXT_ampspervolt.TabIndex = 38;
+ //
+ // label34
+ //
+ this.label34.AutoSize = true;
+ this.label34.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label34.Location = new System.Drawing.Point(5, 81);
+ this.label34.Margin = new System.Windows.Forms.Padding(2, 0, 2, 0);
+ this.label34.Name = "label34";
+ this.label34.Size = new System.Drawing.Size(134, 13);
+ this.label34.TabIndex = 32;
+ this.label34.Text = "4. Voltage divider (Calced):";
+ //
+ // TXT_divider
+ //
+ this.TXT_divider.Location = new System.Drawing.Point(149, 78);
+ this.TXT_divider.Margin = new System.Windows.Forms.Padding(2);
+ this.TXT_divider.Name = "TXT_divider";
+ this.TXT_divider.Size = new System.Drawing.Size(76, 20);
+ this.TXT_divider.TabIndex = 37;
+ //
+ // label35
+ //
+ this.label35.AutoSize = true;
+ this.label35.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label35.Location = new System.Drawing.Point(6, 103);
+ this.label35.Margin = new System.Windows.Forms.Padding(2, 0, 2, 0);
+ this.label35.Name = "label35";
+ this.label35.Size = new System.Drawing.Size(101, 13);
+ this.label35.TabIndex = 33;
+ this.label35.Text = "5. Amperes per volt:";
+ //
+ // TXT_voltage
+ //
+ this.TXT_voltage.Location = new System.Drawing.Point(149, 57);
+ this.TXT_voltage.Margin = new System.Windows.Forms.Padding(2);
+ this.TXT_voltage.Name = "TXT_voltage";
+ this.TXT_voltage.ReadOnly = true;
+ this.TXT_voltage.Size = new System.Drawing.Size(76, 20);
+ this.TXT_voltage.TabIndex = 36;
+ //
+ // TXT_inputvoltage
+ //
+ this.TXT_inputvoltage.Location = new System.Drawing.Point(149, 13);
+ this.TXT_inputvoltage.Margin = new System.Windows.Forms.Padding(2);
+ this.TXT_inputvoltage.Name = "TXT_inputvoltage";
+ this.TXT_inputvoltage.Size = new System.Drawing.Size(76, 20);
+ this.TXT_inputvoltage.TabIndex = 34;
+ //
+ // TXT_measuredvoltage
+ //
+ this.TXT_measuredvoltage.Location = new System.Drawing.Point(149, 35);
+ this.TXT_measuredvoltage.Margin = new System.Windows.Forms.Padding(2);
+ this.TXT_measuredvoltage.Name = "TXT_measuredvoltage";
+ this.TXT_measuredvoltage.Size = new System.Drawing.Size(76, 20);
+ this.TXT_measuredvoltage.TabIndex = 35;
+ //
+ // label47
+ //
+ this.label47.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label47.Location = new System.Drawing.Point(106, 71);
+ this.label47.Name = "label47";
+ this.label47.Size = new System.Drawing.Size(42, 13);
+ this.label47.TabIndex = 49;
+ this.label47.Text = "Sensor";
+ //
+ // CMB_batmonsensortype
+ //
+ this.CMB_batmonsensortype.FormattingEnabled = true;
+ this.CMB_batmonsensortype.Items.AddRange(new object[] {
+ "0: Other",
+ "1: AttoPilot 45A",
+ "2: AttoPilot 90A",
+ "3: AttoPilot 180A"});
+ this.CMB_batmonsensortype.Location = new System.Drawing.Point(160, 68);
+ this.CMB_batmonsensortype.Name = "CMB_batmonsensortype";
+ this.CMB_batmonsensortype.Size = new System.Drawing.Size(121, 21);
+ this.CMB_batmonsensortype.TabIndex = 48;
+ //
+ // textBox3
+ //
+ this.textBox3.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F);
+ this.textBox3.Location = new System.Drawing.Point(282, 172);
+ this.textBox3.Margin = new System.Windows.Forms.Padding(2);
+ this.textBox3.Multiline = true;
+ this.textBox3.Name = "textBox3";
+ this.textBox3.ReadOnly = true;
+ this.textBox3.Size = new System.Drawing.Size(219, 131);
+ this.textBox3.TabIndex = 47;
+ this.textBox3.Text = resources.GetString("textBox3.Text");
+ //
+ // label29
+ //
+ this.label29.AutoSize = true;
+ this.label29.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label29.Location = new System.Drawing.Point(288, 45);
+ this.label29.Name = "label29";
+ this.label29.Size = new System.Drawing.Size(48, 13);
+ this.label29.TabIndex = 43;
+ this.label29.Text = "Capacity";
+ //
+ // label30
+ //
+ this.label30.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label30.Location = new System.Drawing.Point(106, 45);
+ this.label30.Name = "label30";
+ this.label30.Size = new System.Drawing.Size(42, 13);
+ this.label30.TabIndex = 44;
+ this.label30.Text = "Monitor";
+ //
+ // TXT_battcapacity
+ //
+ this.TXT_battcapacity.Location = new System.Drawing.Point(349, 42);
+ this.TXT_battcapacity.Name = "TXT_battcapacity";
+ this.TXT_battcapacity.Size = new System.Drawing.Size(83, 20);
+ this.TXT_battcapacity.TabIndex = 45;
+ //
+ // CMB_batmontype
+ //
+ this.CMB_batmontype.FormattingEnabled = true;
+ this.CMB_batmontype.Items.AddRange(new object[] {
+ "0: Disabled",
+ "3: Battery Volts",
+ "4: Volts & Current"});
+ this.CMB_batmontype.Location = new System.Drawing.Point(160, 41);
+ this.CMB_batmontype.Name = "CMB_batmontype";
+ this.CMB_batmontype.Size = new System.Drawing.Size(121, 21);
+ this.CMB_batmontype.TabIndex = 46;
+ //
+ // pictureBox5
+ //
+ this.pictureBox5.BackColor = System.Drawing.Color.White;
+ this.pictureBox5.BackgroundImage = global::ArdupilotMega.Properties.Resources.attocurrent;
+ this.pictureBox5.BackgroundImageLayout = System.Windows.Forms.ImageLayout.Zoom;
+ this.pictureBox5.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
+ this.pictureBox5.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.pictureBox5.Location = new System.Drawing.Point(14, 16);
+ this.pictureBox5.Name = "pictureBox5";
+ this.pictureBox5.Size = new System.Drawing.Size(75, 75);
+ this.pictureBox5.TabIndex = 42;
+ this.pictureBox5.TabStop = false;
+ //
+ // ConfigBatteryMonitoring
+ //
+ this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+ this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+ this.Controls.Add(this.groupBox4);
+ this.Controls.Add(this.label47);
+ this.Controls.Add(this.CMB_batmonsensortype);
+ this.Controls.Add(this.textBox3);
+ this.Controls.Add(this.label29);
+ this.Controls.Add(this.label30);
+ this.Controls.Add(this.TXT_battcapacity);
+ this.Controls.Add(this.CMB_batmontype);
+ this.Controls.Add(this.pictureBox5);
+ this.Name = "ConfigBatteryMonitoring";
+ this.Size = new System.Drawing.Size(518, 322);
+ this.groupBox4.ResumeLayout(false);
+ this.groupBox4.PerformLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).EndInit();
+ this.ResumeLayout(false);
+ this.PerformLayout();
+
+ }
+
+ #endregion
+
+ private System.Windows.Forms.GroupBox groupBox4;
+ private System.Windows.Forms.Label label31;
+ private System.Windows.Forms.Label label32;
+ private System.Windows.Forms.Label label33;
+ private System.Windows.Forms.TextBox TXT_ampspervolt;
+ private System.Windows.Forms.Label label34;
+ private System.Windows.Forms.TextBox TXT_divider;
+ private System.Windows.Forms.Label label35;
+ private System.Windows.Forms.TextBox TXT_voltage;
+ private System.Windows.Forms.TextBox TXT_inputvoltage;
+ private System.Windows.Forms.TextBox TXT_measuredvoltage;
+ private System.Windows.Forms.Label label47;
+ private System.Windows.Forms.ComboBox CMB_batmonsensortype;
+ private System.Windows.Forms.TextBox textBox3;
+ private System.Windows.Forms.Label label29;
+ private System.Windows.Forms.Label label30;
+ private System.Windows.Forms.TextBox TXT_battcapacity;
+ private System.Windows.Forms.ComboBox CMB_batmontype;
+ private System.Windows.Forms.PictureBox pictureBox5;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs
new file mode 100644
index 0000000000..9ad384538a
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs
@@ -0,0 +1,19 @@
+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.GCSViews.ConfigurationView
+{
+ public partial class ConfigBatteryMonitoring : UserControl
+ {
+ public ConfigBatteryMonitoring()
+ {
+ InitializeComponent();
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx
new file mode 100644
index 0000000000..94b1ff7c8d
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx
@@ -0,0 +1,126 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 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
+
+
+ Voltage sensor calibration:
+To calibrate your sensor, use a multimeter to measure the voltage coming out of your ESC's battery-elimination circuit (these are black and red wires in the three-wire cable that is powering your APM board).
+Then subtract 0.3v from that value and enter it in field #1 at left.
+
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs
new file mode 100644
index 0000000000..829ad3689e
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs
@@ -0,0 +1,450 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class ConfigFlightModes
+ {
+ ///
+ /// 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.components = new System.ComponentModel.Container();
+ this.CB_simple6 = new System.Windows.Forms.CheckBox();
+ this.CB_simple5 = new System.Windows.Forms.CheckBox();
+ this.CB_simple4 = new System.Windows.Forms.CheckBox();
+ this.CB_simple3 = new System.Windows.Forms.CheckBox();
+ this.CB_simple2 = new System.Windows.Forms.CheckBox();
+ this.CB_simple1 = new System.Windows.Forms.CheckBox();
+ this.label14 = new System.Windows.Forms.Label();
+ this.LBL_flightmodepwm = new System.Windows.Forms.Label();
+ this.label13 = new System.Windows.Forms.Label();
+ this.lbl_currentmode = new System.Windows.Forms.Label();
+ this.label12 = new System.Windows.Forms.Label();
+ this.label11 = new System.Windows.Forms.Label();
+ this.label10 = new System.Windows.Forms.Label();
+ this.label9 = new System.Windows.Forms.Label();
+ this.label8 = new System.Windows.Forms.Label();
+ this.label7 = new System.Windows.Forms.Label();
+ this.label6 = new System.Windows.Forms.Label();
+ this.CMB_fmode6 = new System.Windows.Forms.ComboBox();
+ this.label5 = new System.Windows.Forms.Label();
+ this.CMB_fmode5 = new System.Windows.Forms.ComboBox();
+ this.label4 = new System.Windows.Forms.Label();
+ this.CMB_fmode4 = new System.Windows.Forms.ComboBox();
+ this.label3 = new System.Windows.Forms.Label();
+ this.CMB_fmode3 = new System.Windows.Forms.ComboBox();
+ this.label2 = new System.Windows.Forms.Label();
+ this.CMB_fmode2 = new System.Windows.Forms.ComboBox();
+ this.label1 = new System.Windows.Forms.Label();
+ this.CMB_fmode1 = new System.Windows.Forms.ComboBox();
+ this.BUT_SaveModes = new ArdupilotMega.MyButton();
+ this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
+ ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
+ this.SuspendLayout();
+ //
+ // CB_simple6
+ //
+ this.CB_simple6.AutoSize = true;
+ this.CB_simple6.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CB_simple6.Location = new System.Drawing.Point(232, 200);
+ this.CB_simple6.Margin = new System.Windows.Forms.Padding(2);
+ this.CB_simple6.Name = "CB_simple6";
+ this.CB_simple6.Size = new System.Drawing.Size(87, 17);
+ this.CB_simple6.TabIndex = 148;
+ this.CB_simple6.Text = "Simple Mode";
+ this.CB_simple6.UseVisualStyleBackColor = true;
+ //
+ // CB_simple5
+ //
+ this.CB_simple5.AutoSize = true;
+ this.CB_simple5.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CB_simple5.Location = new System.Drawing.Point(232, 173);
+ this.CB_simple5.Margin = new System.Windows.Forms.Padding(2);
+ this.CB_simple5.Name = "CB_simple5";
+ this.CB_simple5.Size = new System.Drawing.Size(87, 17);
+ this.CB_simple5.TabIndex = 147;
+ this.CB_simple5.Text = "Simple Mode";
+ this.CB_simple5.UseVisualStyleBackColor = true;
+ //
+ // CB_simple4
+ //
+ this.CB_simple4.AutoSize = true;
+ this.CB_simple4.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CB_simple4.Location = new System.Drawing.Point(232, 146);
+ this.CB_simple4.Margin = new System.Windows.Forms.Padding(2);
+ this.CB_simple4.Name = "CB_simple4";
+ this.CB_simple4.Size = new System.Drawing.Size(87, 17);
+ this.CB_simple4.TabIndex = 146;
+ this.CB_simple4.Text = "Simple Mode";
+ this.CB_simple4.UseVisualStyleBackColor = true;
+ //
+ // CB_simple3
+ //
+ this.CB_simple3.AutoSize = true;
+ this.CB_simple3.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CB_simple3.Location = new System.Drawing.Point(232, 119);
+ this.CB_simple3.Margin = new System.Windows.Forms.Padding(2);
+ this.CB_simple3.Name = "CB_simple3";
+ this.CB_simple3.Size = new System.Drawing.Size(87, 17);
+ this.CB_simple3.TabIndex = 145;
+ this.CB_simple3.Text = "Simple Mode";
+ this.CB_simple3.UseVisualStyleBackColor = true;
+ //
+ // CB_simple2
+ //
+ this.CB_simple2.AutoSize = true;
+ this.CB_simple2.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CB_simple2.Location = new System.Drawing.Point(232, 92);
+ this.CB_simple2.Margin = new System.Windows.Forms.Padding(2);
+ this.CB_simple2.Name = "CB_simple2";
+ this.CB_simple2.Size = new System.Drawing.Size(87, 17);
+ this.CB_simple2.TabIndex = 144;
+ this.CB_simple2.Text = "Simple Mode";
+ this.CB_simple2.UseVisualStyleBackColor = true;
+ //
+ // CB_simple1
+ //
+ this.CB_simple1.AutoSize = true;
+ this.CB_simple1.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CB_simple1.Location = new System.Drawing.Point(232, 65);
+ this.CB_simple1.Margin = new System.Windows.Forms.Padding(2);
+ this.CB_simple1.Name = "CB_simple1";
+ this.CB_simple1.Size = new System.Drawing.Size(87, 17);
+ this.CB_simple1.TabIndex = 143;
+ this.CB_simple1.Text = "Simple Mode";
+ this.CB_simple1.UseVisualStyleBackColor = true;
+ //
+ // label14
+ //
+ this.label14.AutoSize = true;
+ this.label14.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label14.Location = new System.Drawing.Point(94, 32);
+ this.label14.Name = "label14";
+ this.label14.Size = new System.Drawing.Size(74, 13);
+ this.label14.TabIndex = 142;
+ this.label14.Text = "Current PWM:";
+ //
+ // LBL_flightmodepwm
+ //
+ this.LBL_flightmodepwm.AutoSize = true;
+ this.LBL_flightmodepwm.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.LBL_flightmodepwm.Location = new System.Drawing.Point(174, 32);
+ this.LBL_flightmodepwm.Name = "LBL_flightmodepwm";
+ this.LBL_flightmodepwm.Size = new System.Drawing.Size(13, 13);
+ this.LBL_flightmodepwm.TabIndex = 141;
+ this.LBL_flightmodepwm.Text = "0";
+ //
+ // label13
+ //
+ this.label13.AutoSize = true;
+ this.label13.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label13.Location = new System.Drawing.Point(94, 15);
+ this.label13.Name = "label13";
+ this.label13.Size = new System.Drawing.Size(74, 13);
+ this.label13.TabIndex = 140;
+ this.label13.Text = "Current Mode:";
+ //
+ // lbl_currentmode
+ //
+ this.lbl_currentmode.AutoSize = true;
+ this.lbl_currentmode.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.currentStateBindingSource, "mode", true));
+ this.lbl_currentmode.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.lbl_currentmode.Location = new System.Drawing.Point(174, 15);
+ this.lbl_currentmode.Name = "lbl_currentmode";
+ this.lbl_currentmode.Size = new System.Drawing.Size(42, 13);
+ this.lbl_currentmode.TabIndex = 139;
+ this.lbl_currentmode.Text = "Manual";
+ //
+ // label12
+ //
+ this.label12.AutoSize = true;
+ this.label12.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label12.Location = new System.Drawing.Point(358, 66);
+ this.label12.Name = "label12";
+ this.label12.Size = new System.Drawing.Size(76, 13);
+ this.label12.TabIndex = 138;
+ this.label12.Text = "PWM 0 - 1230";
+ //
+ // label11
+ //
+ this.label11.AutoSize = true;
+ this.label11.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label11.Location = new System.Drawing.Point(358, 201);
+ this.label11.Name = "label11";
+ this.label11.Size = new System.Drawing.Size(70, 13);
+ this.label11.TabIndex = 137;
+ this.label11.Text = "PWM 1750 +";
+ //
+ // label10
+ //
+ this.label10.AutoSize = true;
+ this.label10.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label10.Location = new System.Drawing.Point(358, 174);
+ this.label10.Name = "label10";
+ this.label10.Size = new System.Drawing.Size(94, 13);
+ this.label10.TabIndex = 136;
+ this.label10.Text = "PWM 1621 - 1749";
+ //
+ // label9
+ //
+ this.label9.AutoSize = true;
+ this.label9.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label9.Location = new System.Drawing.Point(358, 147);
+ this.label9.Name = "label9";
+ this.label9.Size = new System.Drawing.Size(94, 13);
+ this.label9.TabIndex = 135;
+ this.label9.Text = "PWM 1491 - 1620";
+ //
+ // label8
+ //
+ this.label8.AutoSize = true;
+ this.label8.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label8.Location = new System.Drawing.Point(358, 120);
+ this.label8.Name = "label8";
+ this.label8.Size = new System.Drawing.Size(94, 13);
+ this.label8.TabIndex = 134;
+ this.label8.Text = "PWM 1361 - 1490";
+ //
+ // label7
+ //
+ this.label7.AutoSize = true;
+ this.label7.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label7.Location = new System.Drawing.Point(358, 93);
+ this.label7.Name = "label7";
+ this.label7.Size = new System.Drawing.Size(94, 13);
+ this.label7.TabIndex = 133;
+ this.label7.Text = "PWM 1231 - 1360";
+ //
+ // label6
+ //
+ this.label6.AutoSize = true;
+ this.label6.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label6.Location = new System.Drawing.Point(20, 201);
+ this.label6.Name = "label6";
+ this.label6.Size = new System.Drawing.Size(71, 13);
+ this.label6.TabIndex = 131;
+ this.label6.Text = "Flight Mode 6";
+ //
+ // CMB_fmode6
+ //
+ this.CMB_fmode6.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+ this.CMB_fmode6.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+ this.CMB_fmode6.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_fmode6.FormattingEnabled = true;
+ this.CMB_fmode6.Location = new System.Drawing.Point(97, 198);
+ this.CMB_fmode6.Name = "CMB_fmode6";
+ this.CMB_fmode6.Size = new System.Drawing.Size(121, 21);
+ this.CMB_fmode6.TabIndex = 130;
+ //
+ // label5
+ //
+ this.label5.AutoSize = true;
+ this.label5.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label5.Location = new System.Drawing.Point(20, 174);
+ this.label5.Name = "label5";
+ this.label5.Size = new System.Drawing.Size(71, 13);
+ this.label5.TabIndex = 129;
+ this.label5.Text = "Flight Mode 5";
+ //
+ // CMB_fmode5
+ //
+ this.CMB_fmode5.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+ this.CMB_fmode5.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+ this.CMB_fmode5.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_fmode5.FormattingEnabled = true;
+ this.CMB_fmode5.Location = new System.Drawing.Point(97, 171);
+ this.CMB_fmode5.Name = "CMB_fmode5";
+ this.CMB_fmode5.Size = new System.Drawing.Size(121, 21);
+ this.CMB_fmode5.TabIndex = 128;
+ //
+ // label4
+ //
+ this.label4.AutoSize = true;
+ this.label4.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label4.Location = new System.Drawing.Point(20, 147);
+ this.label4.Name = "label4";
+ this.label4.Size = new System.Drawing.Size(71, 13);
+ this.label4.TabIndex = 127;
+ this.label4.Text = "Flight Mode 4";
+ //
+ // CMB_fmode4
+ //
+ this.CMB_fmode4.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+ this.CMB_fmode4.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+ this.CMB_fmode4.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_fmode4.FormattingEnabled = true;
+ this.CMB_fmode4.Location = new System.Drawing.Point(97, 144);
+ this.CMB_fmode4.Name = "CMB_fmode4";
+ this.CMB_fmode4.Size = new System.Drawing.Size(121, 21);
+ this.CMB_fmode4.TabIndex = 126;
+ //
+ // label3
+ //
+ this.label3.AutoSize = true;
+ this.label3.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label3.Location = new System.Drawing.Point(20, 120);
+ this.label3.Name = "label3";
+ this.label3.Size = new System.Drawing.Size(71, 13);
+ this.label3.TabIndex = 125;
+ this.label3.Text = "Flight Mode 3";
+ //
+ // CMB_fmode3
+ //
+ this.CMB_fmode3.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+ this.CMB_fmode3.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+ this.CMB_fmode3.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_fmode3.FormattingEnabled = true;
+ this.CMB_fmode3.Location = new System.Drawing.Point(97, 117);
+ this.CMB_fmode3.Name = "CMB_fmode3";
+ this.CMB_fmode3.Size = new System.Drawing.Size(121, 21);
+ this.CMB_fmode3.TabIndex = 124;
+ //
+ // label2
+ //
+ this.label2.AutoSize = true;
+ this.label2.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label2.Location = new System.Drawing.Point(20, 93);
+ this.label2.Name = "label2";
+ this.label2.Size = new System.Drawing.Size(71, 13);
+ this.label2.TabIndex = 123;
+ this.label2.Text = "Flight Mode 2";
+ //
+ // CMB_fmode2
+ //
+ this.CMB_fmode2.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+ this.CMB_fmode2.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+ this.CMB_fmode2.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_fmode2.FormattingEnabled = true;
+ this.CMB_fmode2.Location = new System.Drawing.Point(97, 90);
+ this.CMB_fmode2.Name = "CMB_fmode2";
+ this.CMB_fmode2.Size = new System.Drawing.Size(121, 21);
+ this.CMB_fmode2.TabIndex = 122;
+ //
+ // label1
+ //
+ this.label1.AutoSize = true;
+ this.label1.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label1.Location = new System.Drawing.Point(20, 66);
+ this.label1.Name = "label1";
+ this.label1.Size = new System.Drawing.Size(71, 13);
+ this.label1.TabIndex = 121;
+ this.label1.Text = "Flight Mode 1";
+ //
+ // CMB_fmode1
+ //
+ this.CMB_fmode1.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+ this.CMB_fmode1.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+ this.CMB_fmode1.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_fmode1.FormattingEnabled = true;
+ this.CMB_fmode1.Location = new System.Drawing.Point(97, 63);
+ this.CMB_fmode1.Name = "CMB_fmode1";
+ this.CMB_fmode1.Size = new System.Drawing.Size(121, 21);
+ this.CMB_fmode1.TabIndex = 120;
+ //
+ // BUT_SaveModes
+ //
+ this.BUT_SaveModes.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_SaveModes.Location = new System.Drawing.Point(97, 225);
+ this.BUT_SaveModes.Name = "BUT_SaveModes";
+ this.BUT_SaveModes.Size = new System.Drawing.Size(121, 23);
+ this.BUT_SaveModes.TabIndex = 132;
+ this.BUT_SaveModes.Text = "Save Modes";
+ this.BUT_SaveModes.UseVisualStyleBackColor = true;
+ this.BUT_SaveModes.Click += new System.EventHandler(this.BUT_SaveModes_Click);
+ //
+ // ConfigFlightModes
+ //
+ this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+ this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+ this.Controls.Add(this.CB_simple6);
+ this.Controls.Add(this.CB_simple5);
+ this.Controls.Add(this.CB_simple4);
+ this.Controls.Add(this.CB_simple3);
+ this.Controls.Add(this.CB_simple2);
+ this.Controls.Add(this.CB_simple1);
+ this.Controls.Add(this.label14);
+ this.Controls.Add(this.LBL_flightmodepwm);
+ this.Controls.Add(this.label13);
+ this.Controls.Add(this.lbl_currentmode);
+ this.Controls.Add(this.label12);
+ this.Controls.Add(this.label11);
+ this.Controls.Add(this.label10);
+ this.Controls.Add(this.label9);
+ this.Controls.Add(this.label8);
+ this.Controls.Add(this.label7);
+ this.Controls.Add(this.label6);
+ this.Controls.Add(this.CMB_fmode6);
+ this.Controls.Add(this.label5);
+ this.Controls.Add(this.CMB_fmode5);
+ this.Controls.Add(this.label4);
+ this.Controls.Add(this.CMB_fmode4);
+ this.Controls.Add(this.label3);
+ this.Controls.Add(this.CMB_fmode3);
+ this.Controls.Add(this.label2);
+ this.Controls.Add(this.CMB_fmode2);
+ this.Controls.Add(this.label1);
+ this.Controls.Add(this.CMB_fmode1);
+ this.Controls.Add(this.BUT_SaveModes);
+ this.Name = "ConfigFlightModes";
+ this.Size = new System.Drawing.Size(500, 270);
+ this.Load += new System.EventHandler(this.ConfigFlightModes_Load);
+ ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
+ this.ResumeLayout(false);
+ this.PerformLayout();
+
+ }
+
+ #endregion
+
+ private System.Windows.Forms.CheckBox CB_simple6;
+ private System.Windows.Forms.CheckBox CB_simple5;
+ private System.Windows.Forms.CheckBox CB_simple4;
+ private System.Windows.Forms.CheckBox CB_simple3;
+ private System.Windows.Forms.CheckBox CB_simple2;
+ private System.Windows.Forms.CheckBox CB_simple1;
+ private System.Windows.Forms.Label label14;
+ private System.Windows.Forms.Label LBL_flightmodepwm;
+ private System.Windows.Forms.Label label13;
+ private System.Windows.Forms.Label lbl_currentmode;
+ private System.Windows.Forms.Label label12;
+ private System.Windows.Forms.Label label11;
+ private System.Windows.Forms.Label label10;
+ private System.Windows.Forms.Label label9;
+ private System.Windows.Forms.Label label8;
+ private System.Windows.Forms.Label label7;
+ private System.Windows.Forms.Label label6;
+ private System.Windows.Forms.ComboBox CMB_fmode6;
+ private System.Windows.Forms.Label label5;
+ private System.Windows.Forms.ComboBox CMB_fmode5;
+ private System.Windows.Forms.Label label4;
+ private System.Windows.Forms.ComboBox CMB_fmode4;
+ private System.Windows.Forms.Label label3;
+ private System.Windows.Forms.ComboBox CMB_fmode3;
+ private System.Windows.Forms.Label label2;
+ private System.Windows.Forms.ComboBox CMB_fmode2;
+ private System.Windows.Forms.Label label1;
+ private System.Windows.Forms.ComboBox CMB_fmode1;
+ private MyButton BUT_SaveModes;
+ private System.Windows.Forms.BindingSource currentStateBindingSource;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs
new file mode 100644
index 0000000000..d9acf7002c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs
@@ -0,0 +1,215 @@
+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.GCSViews.ConfigurationView
+{
+ public partial class ConfigFlightModes : UserControl
+ {
+ Timer timer = new Timer();
+
+ public ConfigFlightModes()
+ {
+ InitializeComponent();
+
+ timer.Tick += new EventHandler(timer_Tick);
+
+ timer.Enabled = true;
+ timer.Interval = 100;
+ timer.Start();
+ }
+
+ void timer_Tick(object sender, EventArgs e)
+ {
+ try
+ {
+ MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
+ }
+ catch { }
+
+ float pwm = 0;
+
+ if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
+ {
+ if (MainV2.comPort.param.ContainsKey("FLTMODE_CH"))
+ {
+ switch ((int)(float)MainV2.comPort.param["FLTMODE_CH"])
+ {
+ case 5:
+ pwm = MainV2.cs.ch5in;
+ break;
+ case 6:
+ pwm = MainV2.cs.ch6in;
+ break;
+ case 7:
+ pwm = MainV2.cs.ch7in;
+ break;
+ case 8:
+ pwm = MainV2.cs.ch8in;
+ break;
+ default:
+
+ break;
+ }
+
+ LBL_flightmodepwm.Text = MainV2.comPort.param["FLTMODE_CH"].ToString() + ": " + pwm.ToString();
+ }
+ }
+
+ if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
+ {
+ pwm = MainV2.cs.ch5in;
+ LBL_flightmodepwm.Text = "5: " + MainV2.cs.ch5in.ToString();
+ }
+
+ Control[] fmodelist = new Control[] { CMB_fmode1, CMB_fmode2, CMB_fmode3, CMB_fmode4, CMB_fmode5, CMB_fmode6 };
+
+ foreach (Control ctl in fmodelist)
+ {
+ ctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
+ }
+
+ byte no = readSwitch(pwm);
+
+ fmodelist[no].BackColor = Color.Green;
+ }
+
+ // from arducopter code
+ byte readSwitch(float inpwm)
+ {
+ int pulsewidth = (int)inpwm; // default for Arducopter
+
+ if (pulsewidth > 1230 && pulsewidth <= 1360) return 1;
+ if (pulsewidth > 1360 && pulsewidth <= 1490) return 2;
+ if (pulsewidth > 1490 && pulsewidth <= 1620) return 3;
+ if (pulsewidth > 1620 && pulsewidth <= 1749) return 4; // Software Manual
+ if (pulsewidth >= 1750) return 5; // Hardware Manual
+ return 0;
+ }
+
+ private void BUT_SaveModes_Click(object sender, EventArgs e)
+ {
+ try
+ {
+ if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
+ {
+ MainV2.comPort.setParam("FLTMODE1", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode1.Text));
+ MainV2.comPort.setParam("FLTMODE2", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode2.Text));
+ MainV2.comPort.setParam("FLTMODE3", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode3.Text));
+ MainV2.comPort.setParam("FLTMODE4", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode4.Text));
+ MainV2.comPort.setParam("FLTMODE5", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode5.Text));
+ MainV2.comPort.setParam("FLTMODE6", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode6.Text));
+ }
+ if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
+ {
+ MainV2.comPort.setParam("FLTMODE1", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode1.Text));
+ MainV2.comPort.setParam("FLTMODE2", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode2.Text));
+ MainV2.comPort.setParam("FLTMODE3", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode3.Text));
+ MainV2.comPort.setParam("FLTMODE4", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode4.Text));
+ MainV2.comPort.setParam("FLTMODE5", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode5.Text));
+ MainV2.comPort.setParam("FLTMODE6", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode6.Text));
+
+ float value = (float)(CB_simple1.Checked ? (int)SimpleMode.Simple1 : 0) + (CB_simple2.Checked ? (int)SimpleMode.Simple2 : 0) + (CB_simple3.Checked ? (int)SimpleMode.Simple3 : 0)
+ + (CB_simple4.Checked ? (int)SimpleMode.Simple4 : 0) + (CB_simple5.Checked ? (int)SimpleMode.Simple5 : 0) + (CB_simple6.Checked ? (int)SimpleMode.Simple6 : 0);
+ if (MainV2.comPort.param.ContainsKey("SIMPLE"))
+ MainV2.comPort.setParam("SIMPLE", value);
+ }
+ }
+ catch { CustomMessageBox.Show("Failed to set Flight modes"); }
+ BUT_SaveModes.Text = "Complete";
+ }
+
+ [Flags]
+ public enum SimpleMode
+ {
+ None = 0,
+ Simple1 = 1,
+ Simple2 = 2,
+ Simple3 = 4,
+ Simple4 = 8,
+ Simple5 = 16,
+ Simple6 = 32,
+ }
+
+ private void ConfigFlightModes_Load(object sender, EventArgs e)
+ {
+ if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
+ {
+ CB_simple1.Visible = false;
+ CB_simple2.Visible = false;
+ CB_simple3.Visible = false;
+ CB_simple4.Visible = false;
+ CB_simple5.Visible = false;
+ CB_simple6.Visible = false;
+
+ CMB_fmode1.Items.Clear();
+ CMB_fmode2.Items.Clear();
+ CMB_fmode3.Items.Clear();
+ CMB_fmode4.Items.Clear();
+ CMB_fmode5.Items.Clear();
+ CMB_fmode6.Items.Clear();
+
+ CMB_fmode1.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+ CMB_fmode2.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+ CMB_fmode3.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+ CMB_fmode4.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+ CMB_fmode5.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+ CMB_fmode6.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+
+ try
+ {
+ CMB_fmode1.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE1"].ToString()).ToString();
+ CMB_fmode2.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE2"].ToString()).ToString();
+ CMB_fmode3.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE3"].ToString()).ToString();
+ CMB_fmode4.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE4"].ToString()).ToString();
+ CMB_fmode5.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE5"].ToString()).ToString();
+ CMB_fmode6.Text = Common.apmmodes.MANUAL.ToString();
+ CMB_fmode6.Enabled = false;
+ }
+ catch { }
+ }
+ if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
+ {
+ CMB_fmode1.Items.Clear();
+ CMB_fmode2.Items.Clear();
+ CMB_fmode3.Items.Clear();
+ CMB_fmode4.Items.Clear();
+ CMB_fmode5.Items.Clear();
+ CMB_fmode6.Items.Clear();
+
+ CMB_fmode1.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+ CMB_fmode2.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+ CMB_fmode3.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+ CMB_fmode4.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+ CMB_fmode5.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+ CMB_fmode6.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+
+ try
+ {
+ CMB_fmode1.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE1"].ToString()).ToString();
+ CMB_fmode2.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE2"].ToString()).ToString();
+ CMB_fmode3.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE3"].ToString()).ToString();
+ CMB_fmode4.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE4"].ToString()).ToString();
+ CMB_fmode5.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE5"].ToString()).ToString();
+ CMB_fmode6.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE6"].ToString()).ToString();
+ CMB_fmode6.Enabled = true;
+
+ int simple = int.Parse(MainV2.comPort.param["SIMPLE"].ToString());
+
+ CB_simple1.Checked = ((simple >> 0 & 1) == 1);
+ CB_simple2.Checked = ((simple >> 1 & 1) == 1);
+ CB_simple3.Checked = ((simple >> 2 & 1) == 1);
+ CB_simple4.Checked = ((simple >> 3 & 1) == 1);
+ CB_simple5.Checked = ((simple >> 4 & 1) == 1);
+ CB_simple6.Checked = ((simple >> 5 & 1) == 1);
+ }
+ catch { }
+ }
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx
new file mode 100644
index 0000000000..ff1f88db64
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx
@@ -0,0 +1,126 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 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
+
+
+ 17, 17
+
+
+ 17, 17
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs
new file mode 100644
index 0000000000..909cb77317
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs
@@ -0,0 +1,248 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class ConfigHardwareOptions
+ {
+ ///
+ /// 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.BUT_MagCalibration = new ArdupilotMega.MyButton();
+ this.label27 = new System.Windows.Forms.Label();
+ this.CMB_sonartype = new System.Windows.Forms.ComboBox();
+ this.CHK_enableoptflow = new System.Windows.Forms.CheckBox();
+ this.pictureBox2 = new System.Windows.Forms.PictureBox();
+ this.linkLabelmagdec = new System.Windows.Forms.LinkLabel();
+ this.label100 = new System.Windows.Forms.Label();
+ this.TXT_declination = new System.Windows.Forms.TextBox();
+ this.CHK_enableairspeed = new System.Windows.Forms.CheckBox();
+ this.CHK_enablesonar = new System.Windows.Forms.CheckBox();
+ this.CHK_enablecompass = new System.Windows.Forms.CheckBox();
+ this.pictureBox4 = new System.Windows.Forms.PictureBox();
+ this.pictureBox3 = new System.Windows.Forms.PictureBox();
+ this.pictureBox1 = new System.Windows.Forms.PictureBox();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit();
+ this.SuspendLayout();
+ //
+ // BUT_MagCalibration
+ //
+ this.BUT_MagCalibration.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_MagCalibration.Location = new System.Drawing.Point(340, 13);
+ this.BUT_MagCalibration.Name = "BUT_MagCalibration";
+ this.BUT_MagCalibration.Size = new System.Drawing.Size(75, 23);
+ this.BUT_MagCalibration.TabIndex = 47;
+ this.BUT_MagCalibration.Text = "Calibration";
+ this.BUT_MagCalibration.UseVisualStyleBackColor = true;
+ //
+ // label27
+ //
+ this.label27.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label27.Location = new System.Drawing.Point(445, 45);
+ this.label27.Name = "label27";
+ this.label27.Size = new System.Drawing.Size(150, 20);
+ this.label27.TabIndex = 46;
+ this.label27.Text = "in Degrees eg 2° 3\' W is -2.3";
+ //
+ // CMB_sonartype
+ //
+ this.CMB_sonartype.FormattingEnabled = true;
+ this.CMB_sonartype.Items.AddRange(new object[] {
+ "XL-EZ0",
+ "LV-EZ0",
+ "XL-EZL0"});
+ this.CMB_sonartype.Location = new System.Drawing.Point(243, 122);
+ this.CMB_sonartype.Name = "CMB_sonartype";
+ this.CMB_sonartype.Size = new System.Drawing.Size(121, 21);
+ this.CMB_sonartype.TabIndex = 45;
+ //
+ // CHK_enableoptflow
+ //
+ this.CHK_enableoptflow.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_enableoptflow.Location = new System.Drawing.Point(97, 285);
+ this.CHK_enableoptflow.Name = "CHK_enableoptflow";
+ this.CHK_enableoptflow.Size = new System.Drawing.Size(134, 19);
+ this.CHK_enableoptflow.TabIndex = 44;
+ this.CHK_enableoptflow.Text = "Enable Optical Flow";
+ this.CHK_enableoptflow.UseVisualStyleBackColor = true;
+ //
+ // pictureBox2
+ //
+ this.pictureBox2.BackColor = System.Drawing.Color.White;
+ this.pictureBox2.BackgroundImage = global::ArdupilotMega.Properties.Resources.opticalflow;
+ this.pictureBox2.BackgroundImageLayout = System.Windows.Forms.ImageLayout.Zoom;
+ this.pictureBox2.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
+ this.pictureBox2.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.pictureBox2.Location = new System.Drawing.Point(13, 259);
+ this.pictureBox2.Name = "pictureBox2";
+ this.pictureBox2.Size = new System.Drawing.Size(75, 75);
+ this.pictureBox2.TabIndex = 43;
+ this.pictureBox2.TabStop = false;
+ //
+ // linkLabelmagdec
+ //
+ this.linkLabelmagdec.AutoSize = true;
+ this.linkLabelmagdec.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.linkLabelmagdec.Location = new System.Drawing.Point(325, 68);
+ this.linkLabelmagdec.Name = "linkLabelmagdec";
+ this.linkLabelmagdec.Size = new System.Drawing.Size(104, 13);
+ this.linkLabelmagdec.TabIndex = 42;
+ this.linkLabelmagdec.TabStop = true;
+ this.linkLabelmagdec.Text = "Declination WebSite";
+ //
+ // label100
+ //
+ this.label100.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label100.Location = new System.Drawing.Point(240, 45);
+ this.label100.Name = "label100";
+ this.label100.Size = new System.Drawing.Size(72, 16);
+ this.label100.TabIndex = 38;
+ this.label100.Text = "Declination";
+ //
+ // TXT_declination
+ //
+ this.TXT_declination.Location = new System.Drawing.Point(318, 45);
+ this.TXT_declination.Name = "TXT_declination";
+ this.TXT_declination.Size = new System.Drawing.Size(121, 20);
+ this.TXT_declination.TabIndex = 37;
+ //
+ // CHK_enableairspeed
+ //
+ this.CHK_enableairspeed.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_enableairspeed.Location = new System.Drawing.Point(97, 202);
+ this.CHK_enableairspeed.Name = "CHK_enableairspeed";
+ this.CHK_enableairspeed.Size = new System.Drawing.Size(103, 17);
+ this.CHK_enableairspeed.TabIndex = 39;
+ this.CHK_enableairspeed.Text = "Enable Airspeed";
+ this.CHK_enableairspeed.UseVisualStyleBackColor = true;
+ //
+ // CHK_enablesonar
+ //
+ this.CHK_enablesonar.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_enablesonar.Location = new System.Drawing.Point(94, 124);
+ this.CHK_enablesonar.Name = "CHK_enablesonar";
+ this.CHK_enablesonar.Size = new System.Drawing.Size(90, 17);
+ this.CHK_enablesonar.TabIndex = 40;
+ this.CHK_enablesonar.Text = "Enable Sonar";
+ this.CHK_enablesonar.UseVisualStyleBackColor = true;
+ //
+ // CHK_enablecompass
+ //
+ this.CHK_enablecompass.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_enablecompass.Location = new System.Drawing.Point(97, 44);
+ this.CHK_enablecompass.Name = "CHK_enablecompass";
+ this.CHK_enablecompass.Size = new System.Drawing.Size(105, 17);
+ this.CHK_enablecompass.TabIndex = 41;
+ this.CHK_enablecompass.Text = "Enable Compass";
+ this.CHK_enablecompass.UseVisualStyleBackColor = true;
+ //
+ // pictureBox4
+ //
+ this.pictureBox4.BackColor = System.Drawing.Color.White;
+ this.pictureBox4.BackgroundImage = global::ArdupilotMega.Properties.Resources.airspeed;
+ this.pictureBox4.BackgroundImageLayout = System.Windows.Forms.ImageLayout.Zoom;
+ this.pictureBox4.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
+ this.pictureBox4.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.pictureBox4.Location = new System.Drawing.Point(13, 176);
+ this.pictureBox4.Name = "pictureBox4";
+ this.pictureBox4.Size = new System.Drawing.Size(75, 75);
+ this.pictureBox4.TabIndex = 36;
+ this.pictureBox4.TabStop = false;
+ //
+ // pictureBox3
+ //
+ this.pictureBox3.BackColor = System.Drawing.Color.White;
+ this.pictureBox3.BackgroundImage = global::ArdupilotMega.Properties.Resources.sonar;
+ this.pictureBox3.BackgroundImageLayout = System.Windows.Forms.ImageLayout.Zoom;
+ this.pictureBox3.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
+ this.pictureBox3.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.pictureBox3.Location = new System.Drawing.Point(13, 94);
+ this.pictureBox3.Name = "pictureBox3";
+ this.pictureBox3.Size = new System.Drawing.Size(75, 75);
+ this.pictureBox3.TabIndex = 35;
+ this.pictureBox3.TabStop = false;
+ //
+ // pictureBox1
+ //
+ this.pictureBox1.BackgroundImage = global::ArdupilotMega.Properties.Resources.compass;
+ this.pictureBox1.BackgroundImageLayout = System.Windows.Forms.ImageLayout.Zoom;
+ this.pictureBox1.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
+ this.pictureBox1.ErrorImage = null;
+ this.pictureBox1.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.pictureBox1.InitialImage = null;
+ this.pictureBox1.Location = new System.Drawing.Point(13, 13);
+ this.pictureBox1.Name = "pictureBox1";
+ this.pictureBox1.Size = new System.Drawing.Size(75, 75);
+ this.pictureBox1.TabIndex = 34;
+ this.pictureBox1.TabStop = false;
+ //
+ // ConfigHardwareOptions
+ //
+ this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+ this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+ this.Controls.Add(this.BUT_MagCalibration);
+ this.Controls.Add(this.label27);
+ this.Controls.Add(this.CMB_sonartype);
+ this.Controls.Add(this.CHK_enableoptflow);
+ this.Controls.Add(this.pictureBox2);
+ this.Controls.Add(this.linkLabelmagdec);
+ this.Controls.Add(this.label100);
+ this.Controls.Add(this.TXT_declination);
+ this.Controls.Add(this.CHK_enableairspeed);
+ this.Controls.Add(this.CHK_enablesonar);
+ this.Controls.Add(this.CHK_enablecompass);
+ this.Controls.Add(this.pictureBox4);
+ this.Controls.Add(this.pictureBox3);
+ this.Controls.Add(this.pictureBox1);
+ this.Name = "ConfigHardwareOptions";
+ this.Size = new System.Drawing.Size(602, 351);
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit();
+ this.ResumeLayout(false);
+ this.PerformLayout();
+
+ }
+
+ #endregion
+
+ private MyButton BUT_MagCalibration;
+ private System.Windows.Forms.Label label27;
+ private System.Windows.Forms.ComboBox CMB_sonartype;
+ private System.Windows.Forms.CheckBox CHK_enableoptflow;
+ private System.Windows.Forms.PictureBox pictureBox2;
+ private System.Windows.Forms.LinkLabel linkLabelmagdec;
+ private System.Windows.Forms.Label label100;
+ private System.Windows.Forms.TextBox TXT_declination;
+ private System.Windows.Forms.CheckBox CHK_enableairspeed;
+ private System.Windows.Forms.CheckBox CHK_enablesonar;
+ private System.Windows.Forms.CheckBox CHK_enablecompass;
+ private System.Windows.Forms.PictureBox pictureBox4;
+ private System.Windows.Forms.PictureBox pictureBox3;
+ private System.Windows.Forms.PictureBox pictureBox1;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs
new file mode 100644
index 0000000000..ed884a1ae8
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs
@@ -0,0 +1,49 @@
+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.GCSViews.ConfigurationView
+{
+ public partial class ConfigHardwareOptions : UserControl
+ {
+ public ConfigHardwareOptions()
+ {
+ InitializeComponent();
+ }
+
+ private void CHK_enableoptflow_CheckedChanged(object sender, EventArgs e)
+ {
+
+ }
+
+ private void linkLabel1_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e)
+ {
+
+ }
+
+ private void TXT_declination_Validated(object sender, EventArgs e)
+ {
+
+ }
+
+ private void CHK_enableairspeed_CheckedChanged(object sender, EventArgs e)
+ {
+
+ }
+
+ private void CHK_enablesonar_CheckedChanged(object sender, EventArgs e)
+ {
+
+ }
+
+ private void CHK_enablecompass_CheckedChanged(object sender, EventArgs e)
+ {
+
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx
new file mode 100644
index 0000000000..7080a7d118
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.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/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs
new file mode 100644
index 0000000000..ec5a15499e
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs
@@ -0,0 +1,677 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class ConfigPlanner
+ {
+ ///
+ /// 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.label33 = new System.Windows.Forms.Label();
+ this.CMB_ratesensors = new System.Windows.Forms.ComboBox();
+ this.label26 = new System.Windows.Forms.Label();
+ this.CMB_videoresolutions = new System.Windows.Forms.ComboBox();
+ this.label12 = new System.Windows.Forms.Label();
+ this.CHK_GDIPlus = new System.Windows.Forms.CheckBox();
+ this.label24 = new System.Windows.Forms.Label();
+ this.CHK_loadwponconnect = new System.Windows.Forms.CheckBox();
+ this.label23 = new System.Windows.Forms.Label();
+ this.NUM_tracklength = new System.Windows.Forms.NumericUpDown();
+ this.CHK_speechaltwarning = new System.Windows.Forms.CheckBox();
+ this.label108 = new System.Windows.Forms.Label();
+ this.CHK_resetapmonconnect = new System.Windows.Forms.CheckBox();
+ this.CHK_mavdebug = new System.Windows.Forms.CheckBox();
+ this.label107 = new System.Windows.Forms.Label();
+ this.CMB_raterc = new System.Windows.Forms.ComboBox();
+ this.label104 = new System.Windows.Forms.Label();
+ this.label103 = new System.Windows.Forms.Label();
+ this.label102 = new System.Windows.Forms.Label();
+ this.label101 = new System.Windows.Forms.Label();
+ this.CMB_ratestatus = new System.Windows.Forms.ComboBox();
+ this.CMB_rateposition = new System.Windows.Forms.ComboBox();
+ this.CMB_rateattitude = new System.Windows.Forms.ComboBox();
+ this.label99 = new System.Windows.Forms.Label();
+ this.label98 = new System.Windows.Forms.Label();
+ this.label97 = new System.Windows.Forms.Label();
+ this.CMB_speedunits = new System.Windows.Forms.ComboBox();
+ this.CMB_distunits = new System.Windows.Forms.ComboBox();
+ this.label96 = new System.Windows.Forms.Label();
+ this.label95 = new System.Windows.Forms.Label();
+ this.CHK_speechbattery = new System.Windows.Forms.CheckBox();
+ this.CHK_speechcustom = new System.Windows.Forms.CheckBox();
+ this.CHK_speechmode = new System.Windows.Forms.CheckBox();
+ this.CHK_speechwaypoint = new System.Windows.Forms.CheckBox();
+ this.label94 = new System.Windows.Forms.Label();
+ this.CMB_osdcolor = new System.Windows.Forms.ComboBox();
+ this.CMB_language = new System.Windows.Forms.ComboBox();
+ this.label93 = new System.Windows.Forms.Label();
+ this.CHK_enablespeech = new System.Windows.Forms.CheckBox();
+ this.CHK_hudshow = new System.Windows.Forms.CheckBox();
+ this.label92 = new System.Windows.Forms.Label();
+ this.CMB_videosources = new System.Windows.Forms.ComboBox();
+ this.BUT_Joystick = new ArdupilotMega.MyButton();
+ this.BUT_videostop = new ArdupilotMega.MyButton();
+ this.BUT_videostart = new ArdupilotMega.MyButton();
+ ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).BeginInit();
+ this.SuspendLayout();
+ //
+ // label33
+ //
+ this.label33.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label33.Location = new System.Drawing.Point(517, 246);
+ this.label33.Name = "label33";
+ this.label33.Size = new System.Drawing.Size(43, 13);
+ this.label33.TabIndex = 87;
+ this.label33.Text = "Sensor";
+ //
+ // CMB_ratesensors
+ //
+ this.CMB_ratesensors.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_ratesensors.FormattingEnabled = true;
+ this.CMB_ratesensors.Items.AddRange(new object[] {
+ "0",
+ "1",
+ "3",
+ "10",
+ "50"});
+ this.CMB_ratesensors.Location = new System.Drawing.Point(564, 243);
+ this.CMB_ratesensors.Name = "CMB_ratesensors";
+ this.CMB_ratesensors.Size = new System.Drawing.Size(40, 21);
+ this.CMB_ratesensors.TabIndex = 88;
+ //
+ // label26
+ //
+ this.label26.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label26.Location = new System.Drawing.Point(15, 52);
+ this.label26.Name = "label26";
+ this.label26.Size = new System.Drawing.Size(100, 23);
+ this.label26.TabIndex = 86;
+ this.label26.Text = "Video Format";
+ //
+ // CMB_videoresolutions
+ //
+ this.CMB_videoresolutions.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_videoresolutions.FormattingEnabled = true;
+ this.CMB_videoresolutions.Location = new System.Drawing.Point(124, 49);
+ this.CMB_videoresolutions.Name = "CMB_videoresolutions";
+ this.CMB_videoresolutions.Size = new System.Drawing.Size(408, 21);
+ this.CMB_videoresolutions.TabIndex = 44;
+ //
+ // label12
+ //
+ this.label12.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label12.Location = new System.Drawing.Point(15, 342);
+ this.label12.Name = "label12";
+ this.label12.Size = new System.Drawing.Size(61, 13);
+ this.label12.TabIndex = 84;
+ this.label12.Text = "HUD";
+ //
+ // CHK_GDIPlus
+ //
+ this.CHK_GDIPlus.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_GDIPlus.Location = new System.Drawing.Point(124, 342);
+ this.CHK_GDIPlus.Name = "CHK_GDIPlus";
+ this.CHK_GDIPlus.Size = new System.Drawing.Size(177, 17);
+ this.CHK_GDIPlus.TabIndex = 85;
+ this.CHK_GDIPlus.Text = "GDI+ (old type)";
+ this.CHK_GDIPlus.UseVisualStyleBackColor = true;
+ this.CHK_GDIPlus.CheckedChanged += new System.EventHandler(this.CHK_GDIPlus_CheckedChanged);
+ //
+ // label24
+ //
+ this.label24.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label24.Location = new System.Drawing.Point(15, 320);
+ this.label24.Name = "label24";
+ this.label24.Size = new System.Drawing.Size(61, 13);
+ this.label24.TabIndex = 82;
+ this.label24.Text = "Waypoints";
+ //
+ // CHK_loadwponconnect
+ //
+ this.CHK_loadwponconnect.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_loadwponconnect.Location = new System.Drawing.Point(124, 319);
+ this.CHK_loadwponconnect.Name = "CHK_loadwponconnect";
+ this.CHK_loadwponconnect.Size = new System.Drawing.Size(177, 17);
+ this.CHK_loadwponconnect.TabIndex = 83;
+ this.CHK_loadwponconnect.Text = "Load Waypoints on connect?";
+ this.CHK_loadwponconnect.UseVisualStyleBackColor = true;
+ this.CHK_loadwponconnect.CheckedChanged += new System.EventHandler(this.CHK_loadwponconnect_CheckedChanged);
+ //
+ // label23
+ //
+ this.label23.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label23.Location = new System.Drawing.Point(15, 294);
+ this.label23.Name = "label23";
+ this.label23.Size = new System.Drawing.Size(103, 18);
+ this.label23.TabIndex = 81;
+ this.label23.Text = "Track Length";
+ //
+ // NUM_tracklength
+ //
+ this.NUM_tracklength.Increment = new decimal(new int[] {
+ 100,
+ 0,
+ 0,
+ 0});
+ this.NUM_tracklength.Location = new System.Drawing.Point(124, 293);
+ this.NUM_tracklength.Maximum = new decimal(new int[] {
+ 2000,
+ 0,
+ 0,
+ 0});
+ this.NUM_tracklength.Minimum = new decimal(new int[] {
+ 100,
+ 0,
+ 0,
+ 0});
+ this.NUM_tracklength.Name = "NUM_tracklength";
+ this.NUM_tracklength.Size = new System.Drawing.Size(67, 20);
+ this.NUM_tracklength.TabIndex = 80;
+ this.NUM_tracklength.Value = new decimal(new int[] {
+ 200,
+ 0,
+ 0,
+ 0});
+ this.NUM_tracklength.ValueChanged += new System.EventHandler(this.NUM_tracklength_ValueChanged);
+ //
+ // CHK_speechaltwarning
+ //
+ this.CHK_speechaltwarning.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_speechaltwarning.Location = new System.Drawing.Point(564, 109);
+ this.CHK_speechaltwarning.Name = "CHK_speechaltwarning";
+ this.CHK_speechaltwarning.Size = new System.Drawing.Size(102, 17);
+ this.CHK_speechaltwarning.TabIndex = 79;
+ this.CHK_speechaltwarning.Text = "Alt Warning";
+ this.CHK_speechaltwarning.UseVisualStyleBackColor = true;
+ this.CHK_speechaltwarning.CheckedChanged += new System.EventHandler(this.CHK_speechaltwarning_CheckedChanged);
+ //
+ // label108
+ //
+ this.label108.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label108.Location = new System.Drawing.Point(15, 271);
+ this.label108.Name = "label108";
+ this.label108.Size = new System.Drawing.Size(61, 13);
+ this.label108.TabIndex = 45;
+ this.label108.Text = "APM Reset";
+ //
+ // CHK_resetapmonconnect
+ //
+ this.CHK_resetapmonconnect.Checked = true;
+ this.CHK_resetapmonconnect.CheckState = System.Windows.Forms.CheckState.Checked;
+ this.CHK_resetapmonconnect.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_resetapmonconnect.Location = new System.Drawing.Point(124, 269);
+ this.CHK_resetapmonconnect.Name = "CHK_resetapmonconnect";
+ this.CHK_resetapmonconnect.Size = new System.Drawing.Size(163, 17);
+ this.CHK_resetapmonconnect.TabIndex = 46;
+ this.CHK_resetapmonconnect.Text = "Reset APM on USB Connect";
+ this.CHK_resetapmonconnect.UseVisualStyleBackColor = true;
+ this.CHK_resetapmonconnect.CheckedChanged += new System.EventHandler(this.CHK_resetapmonconnect_CheckedChanged);
+ //
+ // CHK_mavdebug
+ //
+ this.CHK_mavdebug.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left)));
+ this.CHK_mavdebug.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_mavdebug.Location = new System.Drawing.Point(15, 378);
+ this.CHK_mavdebug.Name = "CHK_mavdebug";
+ this.CHK_mavdebug.Size = new System.Drawing.Size(144, 17);
+ this.CHK_mavdebug.TabIndex = 47;
+ this.CHK_mavdebug.Text = "Mavlink Message Debug";
+ this.CHK_mavdebug.UseVisualStyleBackColor = true;
+ this.CHK_mavdebug.CheckedChanged += new System.EventHandler(this.CHK_mavdebug_CheckedChanged);
+ //
+ // label107
+ //
+ this.label107.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label107.Location = new System.Drawing.Point(439, 246);
+ this.label107.Name = "label107";
+ this.label107.Size = new System.Drawing.Size(22, 13);
+ this.label107.TabIndex = 48;
+ this.label107.Text = "RC";
+ //
+ // CMB_raterc
+ //
+ this.CMB_raterc.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_raterc.FormattingEnabled = true;
+ this.CMB_raterc.Items.AddRange(new object[] {
+ "0",
+ "1",
+ "3",
+ "10"});
+ this.CMB_raterc.Location = new System.Drawing.Point(470, 242);
+ this.CMB_raterc.Name = "CMB_raterc";
+ this.CMB_raterc.Size = new System.Drawing.Size(40, 21);
+ this.CMB_raterc.TabIndex = 49;
+ this.CMB_raterc.SelectedIndexChanged += new System.EventHandler(this.CMB_raterc_SelectedIndexChanged);
+ //
+ // label104
+ //
+ this.label104.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label104.Location = new System.Drawing.Point(319, 246);
+ this.label104.Name = "label104";
+ this.label104.Size = new System.Drawing.Size(69, 13);
+ this.label104.TabIndex = 50;
+ this.label104.Text = "Mode/Status";
+ //
+ // label103
+ //
+ this.label103.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label103.Location = new System.Drawing.Point(219, 246);
+ this.label103.Name = "label103";
+ this.label103.Size = new System.Drawing.Size(44, 13);
+ this.label103.TabIndex = 51;
+ this.label103.Text = "Position";
+ //
+ // label102
+ //
+ this.label102.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label102.Location = new System.Drawing.Point(121, 246);
+ this.label102.Name = "label102";
+ this.label102.Size = new System.Drawing.Size(43, 13);
+ this.label102.TabIndex = 52;
+ this.label102.Text = "Attitude";
+ //
+ // label101
+ //
+ this.label101.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label101.Location = new System.Drawing.Point(12, 246);
+ this.label101.Name = "label101";
+ this.label101.Size = new System.Drawing.Size(84, 13);
+ this.label101.TabIndex = 53;
+ this.label101.Text = "Telemetry Rates";
+ //
+ // CMB_ratestatus
+ //
+ this.CMB_ratestatus.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_ratestatus.FormattingEnabled = true;
+ this.CMB_ratestatus.Items.AddRange(new object[] {
+ "0",
+ "1",
+ "3",
+ "10"});
+ this.CMB_ratestatus.Location = new System.Drawing.Point(393, 242);
+ this.CMB_ratestatus.Name = "CMB_ratestatus";
+ this.CMB_ratestatus.Size = new System.Drawing.Size(40, 21);
+ this.CMB_ratestatus.TabIndex = 54;
+ this.CMB_ratestatus.SelectedIndexChanged += new System.EventHandler(this.CMB_ratestatus_SelectedIndexChanged);
+ //
+ // CMB_rateposition
+ //
+ this.CMB_rateposition.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_rateposition.FormattingEnabled = true;
+ this.CMB_rateposition.Items.AddRange(new object[] {
+ "0",
+ "1",
+ "3",
+ "10"});
+ this.CMB_rateposition.Location = new System.Drawing.Point(273, 242);
+ this.CMB_rateposition.Name = "CMB_rateposition";
+ this.CMB_rateposition.Size = new System.Drawing.Size(40, 21);
+ this.CMB_rateposition.TabIndex = 55;
+ this.CMB_rateposition.SelectedIndexChanged += new System.EventHandler(this.CMB_rateposition_SelectedIndexChanged);
+ //
+ // CMB_rateattitude
+ //
+ this.CMB_rateattitude.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_rateattitude.FormattingEnabled = true;
+ this.CMB_rateattitude.Items.AddRange(new object[] {
+ "0",
+ "1",
+ "3",
+ "10"});
+ this.CMB_rateattitude.Location = new System.Drawing.Point(173, 242);
+ this.CMB_rateattitude.Name = "CMB_rateattitude";
+ this.CMB_rateattitude.Size = new System.Drawing.Size(40, 21);
+ this.CMB_rateattitude.TabIndex = 56;
+ this.CMB_rateattitude.SelectedIndexChanged += new System.EventHandler(this.CMB_rateattitude_SelectedIndexChanged);
+ //
+ // label99
+ //
+ this.label99.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label99.Location = new System.Drawing.Point(268, 211);
+ this.label99.Name = "label99";
+ this.label99.Size = new System.Drawing.Size(402, 13);
+ this.label99.TabIndex = 57;
+ this.label99.Text = "NOTE: The Configuration Tab will NOT display these units, as those are raw values" +
+ ".\r\n";
+ //
+ // label98
+ //
+ this.label98.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label98.Location = new System.Drawing.Point(15, 219);
+ this.label98.Name = "label98";
+ this.label98.Size = new System.Drawing.Size(65, 13);
+ this.label98.TabIndex = 58;
+ this.label98.Text = "Speed Units";
+ //
+ // label97
+ //
+ this.label97.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label97.Location = new System.Drawing.Point(15, 191);
+ this.label97.Name = "label97";
+ this.label97.Size = new System.Drawing.Size(52, 13);
+ this.label97.TabIndex = 59;
+ this.label97.Text = "Dist Units";
+ //
+ // CMB_speedunits
+ //
+ this.CMB_speedunits.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_speedunits.FormattingEnabled = true;
+ this.CMB_speedunits.Location = new System.Drawing.Point(124, 216);
+ this.CMB_speedunits.Name = "CMB_speedunits";
+ this.CMB_speedunits.Size = new System.Drawing.Size(138, 21);
+ this.CMB_speedunits.TabIndex = 60;
+ this.CMB_speedunits.SelectedIndexChanged += new System.EventHandler(this.CMB_speedunits_SelectedIndexChanged);
+ //
+ // CMB_distunits
+ //
+ this.CMB_distunits.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_distunits.FormattingEnabled = true;
+ this.CMB_distunits.Location = new System.Drawing.Point(124, 189);
+ this.CMB_distunits.Name = "CMB_distunits";
+ this.CMB_distunits.Size = new System.Drawing.Size(138, 21);
+ this.CMB_distunits.TabIndex = 61;
+ this.CMB_distunits.SelectedIndexChanged += new System.EventHandler(this.CMB_distunits_SelectedIndexChanged);
+ //
+ // label96
+ //
+ this.label96.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label96.Location = new System.Drawing.Point(15, 164);
+ this.label96.Name = "label96";
+ this.label96.Size = new System.Drawing.Size(45, 13);
+ this.label96.TabIndex = 62;
+ this.label96.Text = "Joystick";
+ //
+ // label95
+ //
+ this.label95.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label95.Location = new System.Drawing.Point(15, 113);
+ this.label95.Name = "label95";
+ this.label95.Size = new System.Drawing.Size(44, 13);
+ this.label95.TabIndex = 63;
+ this.label95.Text = "Speech";
+ //
+ // CHK_speechbattery
+ //
+ this.CHK_speechbattery.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_speechbattery.Location = new System.Drawing.Point(456, 109);
+ this.CHK_speechbattery.Name = "CHK_speechbattery";
+ this.CHK_speechbattery.Size = new System.Drawing.Size(102, 17);
+ this.CHK_speechbattery.TabIndex = 64;
+ this.CHK_speechbattery.Text = "Battery Warning";
+ this.CHK_speechbattery.UseVisualStyleBackColor = true;
+ this.CHK_speechbattery.CheckedChanged += new System.EventHandler(this.CHK_speechbattery_CheckedChanged);
+ //
+ // CHK_speechcustom
+ //
+ this.CHK_speechcustom.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_speechcustom.Location = new System.Drawing.Point(363, 109);
+ this.CHK_speechcustom.Name = "CHK_speechcustom";
+ this.CHK_speechcustom.Size = new System.Drawing.Size(87, 17);
+ this.CHK_speechcustom.TabIndex = 65;
+ this.CHK_speechcustom.Text = "Time Interval";
+ this.CHK_speechcustom.UseVisualStyleBackColor = true;
+ this.CHK_speechcustom.CheckedChanged += new System.EventHandler(this.CHK_speechcustom_CheckedChanged);
+ //
+ // CHK_speechmode
+ //
+ this.CHK_speechmode.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_speechmode.Location = new System.Drawing.Point(307, 109);
+ this.CHK_speechmode.Name = "CHK_speechmode";
+ this.CHK_speechmode.Size = new System.Drawing.Size(56, 17);
+ this.CHK_speechmode.TabIndex = 66;
+ this.CHK_speechmode.Text = "Mode ";
+ this.CHK_speechmode.UseVisualStyleBackColor = true;
+ this.CHK_speechmode.CheckedChanged += new System.EventHandler(this.CHK_speechmode_CheckedChanged);
+ //
+ // CHK_speechwaypoint
+ //
+ this.CHK_speechwaypoint.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_speechwaypoint.Location = new System.Drawing.Point(230, 109);
+ this.CHK_speechwaypoint.Name = "CHK_speechwaypoint";
+ this.CHK_speechwaypoint.Size = new System.Drawing.Size(71, 17);
+ this.CHK_speechwaypoint.TabIndex = 67;
+ this.CHK_speechwaypoint.Text = "Waypoint";
+ this.CHK_speechwaypoint.UseVisualStyleBackColor = true;
+ this.CHK_speechwaypoint.CheckedChanged += new System.EventHandler(this.CHK_speechwaypoint_CheckedChanged);
+ //
+ // label94
+ //
+ this.label94.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label94.Location = new System.Drawing.Point(15, 85);
+ this.label94.Name = "label94";
+ this.label94.Size = new System.Drawing.Size(57, 13);
+ this.label94.TabIndex = 68;
+ this.label94.Text = "OSD Color";
+ //
+ // CMB_osdcolor
+ //
+ this.CMB_osdcolor.DrawMode = System.Windows.Forms.DrawMode.OwnerDrawFixed;
+ this.CMB_osdcolor.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_osdcolor.FormattingEnabled = true;
+ this.CMB_osdcolor.Location = new System.Drawing.Point(124, 82);
+ this.CMB_osdcolor.Name = "CMB_osdcolor";
+ this.CMB_osdcolor.Size = new System.Drawing.Size(138, 21);
+ this.CMB_osdcolor.TabIndex = 69;
+ this.CMB_osdcolor.SelectedIndexChanged += new System.EventHandler(this.CMB_osdcolor_SelectedIndexChanged);
+ //
+ // CMB_language
+ //
+ this.CMB_language.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_language.FormattingEnabled = true;
+ this.CMB_language.Location = new System.Drawing.Point(124, 133);
+ this.CMB_language.Name = "CMB_language";
+ this.CMB_language.Size = new System.Drawing.Size(138, 21);
+ this.CMB_language.TabIndex = 70;
+ this.CMB_language.SelectedIndexChanged += new System.EventHandler(this.CMB_language_SelectedIndexChanged);
+ //
+ // label93
+ //
+ this.label93.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label93.Location = new System.Drawing.Point(15, 137);
+ this.label93.Name = "label93";
+ this.label93.Size = new System.Drawing.Size(69, 13);
+ this.label93.TabIndex = 71;
+ this.label93.Text = "UI Language";
+ //
+ // CHK_enablespeech
+ //
+ this.CHK_enablespeech.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_enablespeech.Location = new System.Drawing.Point(124, 109);
+ this.CHK_enablespeech.Name = "CHK_enablespeech";
+ this.CHK_enablespeech.Size = new System.Drawing.Size(99, 17);
+ this.CHK_enablespeech.TabIndex = 72;
+ this.CHK_enablespeech.Text = "Enable Speech";
+ this.CHK_enablespeech.UseVisualStyleBackColor = true;
+ this.CHK_enablespeech.CheckedChanged += new System.EventHandler(this.CHK_enablespeech_CheckedChanged);
+ //
+ // CHK_hudshow
+ //
+ this.CHK_hudshow.Checked = true;
+ this.CHK_hudshow.CheckState = System.Windows.Forms.CheckState.Checked;
+ this.CHK_hudshow.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_hudshow.Location = new System.Drawing.Point(537, 17);
+ this.CHK_hudshow.Name = "CHK_hudshow";
+ this.CHK_hudshow.Size = new System.Drawing.Size(125, 17);
+ this.CHK_hudshow.TabIndex = 73;
+ this.CHK_hudshow.Text = "Enable HUD Overlay";
+ this.CHK_hudshow.UseVisualStyleBackColor = true;
+ this.CHK_hudshow.Click += new System.EventHandler(this.CHK_hudshow_CheckedChanged);
+ //
+ // label92
+ //
+ this.label92.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label92.Location = new System.Drawing.Point(15, 18);
+ this.label92.Name = "label92";
+ this.label92.Size = new System.Drawing.Size(100, 23);
+ this.label92.TabIndex = 74;
+ this.label92.Text = "Video Device";
+ //
+ // CMB_videosources
+ //
+ this.CMB_videosources.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CMB_videosources.FormattingEnabled = true;
+ this.CMB_videosources.Location = new System.Drawing.Point(124, 15);
+ this.CMB_videosources.Name = "CMB_videosources";
+ this.CMB_videosources.Size = new System.Drawing.Size(245, 21);
+ this.CMB_videosources.TabIndex = 75;
+ this.CMB_videosources.SelectedIndexChanged += new System.EventHandler(this.CMB_videosources_SelectedIndexChanged);
+ //
+ // BUT_Joystick
+ //
+ this.BUT_Joystick.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_Joystick.Location = new System.Drawing.Point(124, 160);
+ this.BUT_Joystick.Name = "BUT_Joystick";
+ this.BUT_Joystick.Size = new System.Drawing.Size(99, 23);
+ this.BUT_Joystick.TabIndex = 76;
+ this.BUT_Joystick.Text = "Joystick Setup";
+ this.BUT_Joystick.UseVisualStyleBackColor = true;
+ this.BUT_Joystick.Click += new System.EventHandler(this.BUT_Joystick_Click);
+ //
+ // BUT_videostop
+ //
+ this.BUT_videostop.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_videostop.Location = new System.Drawing.Point(456, 13);
+ this.BUT_videostop.Name = "BUT_videostop";
+ this.BUT_videostop.Size = new System.Drawing.Size(75, 23);
+ this.BUT_videostop.TabIndex = 77;
+ this.BUT_videostop.Text = "Stop";
+ this.BUT_videostop.UseVisualStyleBackColor = true;
+ this.BUT_videostop.Click += new System.EventHandler(this.BUT_videostop_Click);
+ //
+ // BUT_videostart
+ //
+ this.BUT_videostart.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_videostart.Location = new System.Drawing.Point(375, 13);
+ this.BUT_videostart.Name = "BUT_videostart";
+ this.BUT_videostart.Size = new System.Drawing.Size(75, 23);
+ this.BUT_videostart.TabIndex = 78;
+ this.BUT_videostart.Text = "Start";
+ this.BUT_videostart.UseVisualStyleBackColor = true;
+ this.BUT_videostart.Click += new System.EventHandler(this.BUT_videostart_Click);
+ //
+ // ConfigPlanner
+ //
+ this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+ this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+ this.Controls.Add(this.label33);
+ this.Controls.Add(this.CMB_ratesensors);
+ this.Controls.Add(this.label26);
+ this.Controls.Add(this.CMB_videoresolutions);
+ this.Controls.Add(this.label12);
+ this.Controls.Add(this.CHK_GDIPlus);
+ this.Controls.Add(this.label24);
+ this.Controls.Add(this.CHK_loadwponconnect);
+ this.Controls.Add(this.label23);
+ this.Controls.Add(this.NUM_tracklength);
+ this.Controls.Add(this.CHK_speechaltwarning);
+ this.Controls.Add(this.label108);
+ this.Controls.Add(this.CHK_resetapmonconnect);
+ this.Controls.Add(this.CHK_mavdebug);
+ this.Controls.Add(this.label107);
+ this.Controls.Add(this.CMB_raterc);
+ this.Controls.Add(this.label104);
+ this.Controls.Add(this.label103);
+ this.Controls.Add(this.label102);
+ this.Controls.Add(this.label101);
+ this.Controls.Add(this.CMB_ratestatus);
+ this.Controls.Add(this.CMB_rateposition);
+ this.Controls.Add(this.CMB_rateattitude);
+ this.Controls.Add(this.label99);
+ this.Controls.Add(this.label98);
+ this.Controls.Add(this.label97);
+ this.Controls.Add(this.CMB_speedunits);
+ this.Controls.Add(this.CMB_distunits);
+ this.Controls.Add(this.label96);
+ this.Controls.Add(this.label95);
+ this.Controls.Add(this.CHK_speechbattery);
+ this.Controls.Add(this.CHK_speechcustom);
+ this.Controls.Add(this.CHK_speechmode);
+ this.Controls.Add(this.CHK_speechwaypoint);
+ this.Controls.Add(this.label94);
+ this.Controls.Add(this.CMB_osdcolor);
+ this.Controls.Add(this.CMB_language);
+ this.Controls.Add(this.label93);
+ this.Controls.Add(this.CHK_enablespeech);
+ this.Controls.Add(this.CHK_hudshow);
+ this.Controls.Add(this.label92);
+ this.Controls.Add(this.CMB_videosources);
+ this.Controls.Add(this.BUT_Joystick);
+ this.Controls.Add(this.BUT_videostop);
+ this.Controls.Add(this.BUT_videostart);
+ this.Name = "ConfigPlanner";
+ this.Size = new System.Drawing.Size(682, 398);
+ ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).EndInit();
+ this.ResumeLayout(false);
+
+ }
+
+ #endregion
+
+ private System.Windows.Forms.Label label33;
+ private System.Windows.Forms.ComboBox CMB_ratesensors;
+ private System.Windows.Forms.Label label26;
+ private System.Windows.Forms.ComboBox CMB_videoresolutions;
+ private System.Windows.Forms.Label label12;
+ private System.Windows.Forms.CheckBox CHK_GDIPlus;
+ private System.Windows.Forms.Label label24;
+ private System.Windows.Forms.CheckBox CHK_loadwponconnect;
+ private System.Windows.Forms.Label label23;
+ private System.Windows.Forms.NumericUpDown NUM_tracklength;
+ private System.Windows.Forms.CheckBox CHK_speechaltwarning;
+ private System.Windows.Forms.Label label108;
+ private System.Windows.Forms.CheckBox CHK_resetapmonconnect;
+ private System.Windows.Forms.CheckBox CHK_mavdebug;
+ private System.Windows.Forms.Label label107;
+ private System.Windows.Forms.ComboBox CMB_raterc;
+ private System.Windows.Forms.Label label104;
+ private System.Windows.Forms.Label label103;
+ private System.Windows.Forms.Label label102;
+ private System.Windows.Forms.Label label101;
+ private System.Windows.Forms.ComboBox CMB_ratestatus;
+ private System.Windows.Forms.ComboBox CMB_rateposition;
+ private System.Windows.Forms.ComboBox CMB_rateattitude;
+ private System.Windows.Forms.Label label99;
+ private System.Windows.Forms.Label label98;
+ private System.Windows.Forms.Label label97;
+ private System.Windows.Forms.ComboBox CMB_speedunits;
+ private System.Windows.Forms.ComboBox CMB_distunits;
+ private System.Windows.Forms.Label label96;
+ private System.Windows.Forms.Label label95;
+ private System.Windows.Forms.CheckBox CHK_speechbattery;
+ private System.Windows.Forms.CheckBox CHK_speechcustom;
+ private System.Windows.Forms.CheckBox CHK_speechmode;
+ private System.Windows.Forms.CheckBox CHK_speechwaypoint;
+ private System.Windows.Forms.Label label94;
+ private System.Windows.Forms.ComboBox CMB_osdcolor;
+ private System.Windows.Forms.ComboBox CMB_language;
+ private System.Windows.Forms.Label label93;
+ private System.Windows.Forms.CheckBox CHK_enablespeech;
+ private System.Windows.Forms.CheckBox CHK_hudshow;
+ private System.Windows.Forms.Label label92;
+ private System.Windows.Forms.ComboBox CMB_videosources;
+ private MyButton BUT_Joystick;
+ private MyButton BUT_videostop;
+ private MyButton BUT_videostart;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
new file mode 100644
index 0000000000..5040d85be5
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
@@ -0,0 +1,372 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Globalization;
+using System.Linq;
+using System.Runtime.InteropServices;
+using System.Text;
+using System.Windows.Forms;
+using DirectShowLib;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ public partial class ConfigPlanner : UserControl
+ {
+ // AR todo: replicate this functionality
+ private bool startup = false;
+
+ public ConfigPlanner()
+ {
+ InitializeComponent();
+ }
+
+
+ private void BUT_videostart_Click(object sender, EventArgs e)
+ {
+ // stop first
+ BUT_videostop_Click(sender, e);
+
+ var bmp = (GCSViews.Configuration.GCSBitmapInfo)CMB_videoresolutions.SelectedItem;
+
+ try
+ {
+ MainV2.cam = new WebCamService.Capture(CMB_videosources.SelectedIndex, bmp.Media);
+
+ MainV2.cam.showhud = CHK_hudshow.Checked;
+
+ MainV2.cam.Start();
+
+ MainV2.config["video_options"] = CMB_videoresolutions.SelectedIndex;
+
+ BUT_videostart.Enabled = false;
+ }
+ catch (Exception ex) { CustomMessageBox.Show("Camera Fail: " + ex.Message); }
+
+ }
+
+ private void BUT_videostop_Click(object sender, EventArgs e)
+ {
+ BUT_videostart.Enabled = true;
+ if (MainV2.cam != null)
+ {
+ MainV2.cam.Dispose();
+ MainV2.cam = null;
+ }
+ }
+
+ private void CMB_videosources_MouseClick(object sender, MouseEventArgs e)
+ {
+ // the reason why i dont populate this list is because on linux/mac this call will fail.
+ WebCamService.Capture capt = new WebCamService.Capture();
+
+ List devices = WebCamService.Capture.getDevices();
+
+ CMB_videosources.DataSource = devices;
+
+ capt.Dispose();
+ }
+
+ private void CMB_videosources_SelectedIndexChanged(object sender, EventArgs e)
+ {
+ int hr;
+ int count;
+ int size;
+ object o;
+ IBaseFilter capFilter = null;
+ ICaptureGraphBuilder2 capGraph = null;
+ AMMediaType media = null;
+ VideoInfoHeader v;
+ VideoStreamConfigCaps c;
+ List modes = new List();
+
+ // Get the ICaptureGraphBuilder2
+ capGraph = (ICaptureGraphBuilder2)new CaptureGraphBuilder2();
+ IFilterGraph2 m_FilterGraph = (IFilterGraph2)new FilterGraph();
+
+ DsDevice[] capDevices;
+ capDevices = DsDevice.GetDevicesOfCat(FilterCategory.VideoInputDevice);
+
+ // Add the video device
+ hr = m_FilterGraph.AddSourceFilterForMoniker(capDevices[CMB_videosources.SelectedIndex].Mon, null, "Video input", out capFilter);
+ try
+ {
+ DsError.ThrowExceptionForHR(hr);
+ }
+ catch (Exception ex)
+ {
+ CustomMessageBox.Show("Can not add video source\n" + ex.ToString());
+ return;
+ }
+
+ // Find the stream config interface
+ hr = capGraph.FindInterface(PinCategory.Capture, MediaType.Video, capFilter, typeof(IAMStreamConfig).GUID, out o);
+ DsError.ThrowExceptionForHR(hr);
+
+ IAMStreamConfig videoStreamConfig = o as IAMStreamConfig;
+ if (videoStreamConfig == null)
+ {
+ throw new Exception("Failed to get IAMStreamConfig");
+ }
+
+ hr = videoStreamConfig.GetNumberOfCapabilities(out count, out size);
+ DsError.ThrowExceptionForHR(hr);
+ IntPtr TaskMemPointer = Marshal.AllocCoTaskMem(size);
+ for (int i = 0; i < count; i++)
+ {
+ IntPtr ptr = IntPtr.Zero;
+
+ hr = videoStreamConfig.GetStreamCaps(i, out media, TaskMemPointer);
+ v = (VideoInfoHeader)Marshal.PtrToStructure(media.formatPtr, typeof(VideoInfoHeader));
+ c = (VideoStreamConfigCaps)Marshal.PtrToStructure(TaskMemPointer, typeof(VideoStreamConfigCaps));
+ modes.Add(new GCSViews.Configuration.GCSBitmapInfo(v.BmiHeader.Width, v.BmiHeader.Height, c.MaxFrameInterval, c.VideoStandard.ToString(), media));
+ }
+ Marshal.FreeCoTaskMem(TaskMemPointer);
+ DsUtils.FreeAMMediaType(media);
+
+ CMB_videoresolutions.DataSource = modes;
+
+ if (MainV2.getConfig("video_options") != "" && CMB_videosources.Text != "")
+ {
+ CMB_videoresolutions.SelectedIndex = int.Parse(MainV2.getConfig("video_options"));
+ }
+ }
+
+ private void CHK_hudshow_CheckedChanged(object sender, EventArgs e)
+ {
+ GCSViews.FlightData.myhud.hudon = CHK_hudshow.Checked;
+ }
+
+ private void CHK_enablespeech_CheckedChanged(object sender, EventArgs e)
+ {
+ MainV2.speechEnable = CHK_enablespeech.Checked;
+ MainV2.config["speechenable"] = CHK_enablespeech.Checked;
+ if (MainV2.speechEngine != null)
+ MainV2.speechEngine.SpeakAsyncCancelAll();
+ }
+
+ private void CMB_language_SelectedIndexChanged(object sender, EventArgs e)
+ {
+ MainV2.instance.changelanguage((CultureInfo)CMB_language.SelectedItem);
+
+#if !DEBUG
+ MessageBox.Show("Please Restart the Planner");
+
+ Application.Exit();
+#endif
+ }
+
+ private void CMB_osdcolor_SelectedIndexChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ if (CMB_osdcolor.Text != "")
+ {
+ MainV2.config["hudcolor"] = CMB_osdcolor.Text;
+ GCSViews.FlightData.myhud.hudcolor = Color.FromKnownColor((KnownColor)Enum.Parse(typeof(KnownColor), CMB_osdcolor.Text));
+ }
+ }
+
+ private void CHK_speechwaypoint_CheckedChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ MainV2.config["speechwaypointenabled"] = ((CheckBox)sender).Checked.ToString();
+
+ if (((CheckBox)sender).Checked)
+ {
+ string speechstring = "Heading to Waypoint {wpn}";
+ if (MainV2.config["speechwaypoint"] != null)
+ speechstring = MainV2.config["speechwaypoint"].ToString();
+ Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
+ MainV2.config["speechwaypoint"] = speechstring;
+ }
+ }
+
+ private void CHK_speechmode_CheckedChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ MainV2.config["speechmodeenabled"] = ((CheckBox)sender).Checked.ToString();
+
+ if (((CheckBox)sender).Checked)
+ {
+ string speechstring = "Mode changed to {mode}";
+ if (MainV2.config["speechmode"] != null)
+ speechstring = MainV2.config["speechmode"].ToString();
+ Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
+ MainV2.config["speechmode"] = speechstring;
+ }
+ }
+
+ private void CHK_speechcustom_CheckedChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ MainV2.config["speechcustomenabled"] = ((CheckBox)sender).Checked.ToString();
+
+ if (((CheckBox)sender).Checked)
+ {
+ string speechstring = "Heading to Waypoint {wpn}, altitude is {alt}, Ground speed is {gsp} ";
+ if (MainV2.config["speechcustom"] != null)
+ speechstring = MainV2.config["speechcustom"].ToString();
+ Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
+ MainV2.config["speechcustom"] = speechstring;
+ }
+ }
+
+ private void BUT_rerequestparams_Click(object sender, EventArgs e)
+ {
+ if (!MainV2.comPort.BaseStream.IsOpen)
+ return;
+ ((MyButton)sender).Enabled = false;
+ try
+ {
+
+ MainV2.comPort.getParamList();
+
+
+
+
+ }
+ catch { CustomMessageBox.Show("Error: getting param list"); }
+
+
+ ((MyButton)sender).Enabled = true;
+ startup = true;
+
+ // AR todo: fix this up
+ //Configuration_Load(null, null);
+ }
+
+ private void CHK_speechbattery_CheckedChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ MainV2.config["speechbatteryenabled"] = ((CheckBox)sender).Checked.ToString();
+
+ if (((CheckBox)sender).Checked)
+ {
+ string speechstring = "WARNING, Battery at {batv} Volt";
+ if (MainV2.config["speechbattery"] != null)
+ speechstring = MainV2.config["speechbattery"].ToString();
+ Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
+ MainV2.config["speechbattery"] = speechstring;
+
+ speechstring = "9.6";
+ if (MainV2.config["speechbatteryvolt"] != null)
+ speechstring = MainV2.config["speechbatteryvolt"].ToString();
+ Common.InputBox("Battery Level", "What Voltage do you want to warn at?", ref speechstring);
+ MainV2.config["speechbatteryvolt"] = speechstring;
+
+ }
+ }
+
+ private void BUT_Joystick_Click(object sender, EventArgs e)
+ {
+ Form joy = new JoystickSetup();
+ ThemeManager.ApplyThemeTo(joy);
+ joy.Show();
+ }
+
+ private void CMB_distunits_SelectedIndexChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ MainV2.config["distunits"] = CMB_distunits.Text;
+ MainV2.instance.changeunits();
+ }
+
+ private void CMB_speedunits_SelectedIndexChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ MainV2.config["speedunits"] = CMB_speedunits.Text;
+ MainV2.instance.changeunits();
+ }
+
+ private void CMB_rateattitude_SelectedIndexChanged(object sender, EventArgs e)
+ {
+ MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
+ MainV2.cs.rateattitude = byte.Parse(((ComboBox)sender).Text);
+ }
+
+ private void CMB_rateposition_SelectedIndexChanged(object sender, EventArgs e)
+ {
+ MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
+ MainV2.cs.rateposition = byte.Parse(((ComboBox)sender).Text);
+ }
+
+ private void CMB_ratestatus_SelectedIndexChanged(object sender, EventArgs e)
+ {
+ MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
+ MainV2.cs.ratestatus = byte.Parse(((ComboBox)sender).Text);
+ }
+
+ private void CMB_raterc_SelectedIndexChanged(object sender, EventArgs e)
+ {
+ MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
+ MainV2.cs.raterc = byte.Parse(((ComboBox)sender).Text);
+ }
+
+ private void CMB_ratesensors_SelectedIndexChanged(object sender, EventArgs e)
+ {
+ MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
+ MainV2.cs.ratesensors = byte.Parse(((ComboBox)sender).Text);
+ }
+
+ private void CHK_mavdebug_CheckedChanged(object sender, EventArgs e)
+ {
+ MainV2.comPort.debugmavlink = CHK_mavdebug.Checked;
+ }
+
+ private void CHK_resetapmonconnect_CheckedChanged(object sender, EventArgs e)
+ {
+ MainV2.config[((CheckBox)sender).Name] = ((CheckBox)sender).Checked.ToString();
+ }
+
+ private void CHK_speechaltwarning_CheckedChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ MainV2.config["speechaltenabled"] = ((CheckBox)sender).Checked.ToString();
+
+ if (((CheckBox)sender).Checked)
+ {
+ string speechstring = "WARNING, low altitude {alt}";
+ if (MainV2.config["speechalt"] != null)
+ speechstring = MainV2.config["speechalt"].ToString();
+ Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
+ MainV2.config["speechalt"] = speechstring;
+
+ speechstring = "2";
+ if (MainV2.config["speechaltheight"] != null)
+ speechstring = MainV2.config["speechaltheight"].ToString();
+ Common.InputBox("Min Alt", "What altitude do you want to warn at? (relative to home)", ref speechstring);
+ MainV2.config["speechaltheight"] = (double.Parse(speechstring) / MainV2.cs.multiplierdist).ToString(); // save as m
+
+ }
+ }
+
+ private void NUM_tracklength_ValueChanged(object sender, EventArgs e)
+ {
+ MainV2.config["NUM_tracklength"] = NUM_tracklength.Value.ToString();
+
+ }
+
+ private void CHK_loadwponconnect_CheckedChanged(object sender, EventArgs e)
+ {
+ MainV2.config["loadwpsonconnect"] = CHK_loadwponconnect.Checked.ToString();
+ }
+
+ private void CHK_GDIPlus_CheckedChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ CustomMessageBox.Show("You need to restart the planner for this to take effect");
+ MainV2.config["CHK_GDIPlus"] = CHK_GDIPlus.Checked.ToString();
+ }
+
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx
new file mode 100644
index 0000000000..7080a7d118
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.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/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs
new file mode 100644
index 0000000000..04dca22d3e
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs
@@ -0,0 +1,366 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class ConfigRadioInput
+ {
+ ///
+ /// 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.components = new System.ComponentModel.Container();
+ this.groupBoxElevons = new System.Windows.Forms.GroupBox();
+ this.CHK_mixmode = new System.Windows.Forms.CheckBox();
+ this.CHK_elevonch2rev = new System.Windows.Forms.CheckBox();
+ this.CHK_elevonrev = new System.Windows.Forms.CheckBox();
+ this.CHK_elevonch1rev = new System.Windows.Forms.CheckBox();
+ this.CHK_revch3 = new System.Windows.Forms.CheckBox();
+ this.CHK_revch4 = new System.Windows.Forms.CheckBox();
+ this.CHK_revch2 = new System.Windows.Forms.CheckBox();
+ this.CHK_revch1 = new System.Windows.Forms.CheckBox();
+ this.BUT_Calibrateradio = new ArdupilotMega.MyButton();
+ this.BAR8 = new ArdupilotMega.HorizontalProgressBar2();
+ this.BAR7 = new ArdupilotMega.HorizontalProgressBar2();
+ this.BAR6 = new ArdupilotMega.HorizontalProgressBar2();
+ this.BAR5 = new ArdupilotMega.HorizontalProgressBar2();
+ this.BARpitch = new ArdupilotMega.VerticalProgressBar2();
+ this.BARthrottle = new ArdupilotMega.VerticalProgressBar2();
+ this.BARyaw = new ArdupilotMega.HorizontalProgressBar2();
+ this.BARroll = new ArdupilotMega.HorizontalProgressBar2();
+ this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
+ this.groupBoxElevons.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
+ this.SuspendLayout();
+ //
+ // groupBoxElevons
+ //
+ this.groupBoxElevons.Controls.Add(this.CHK_mixmode);
+ this.groupBoxElevons.Controls.Add(this.CHK_elevonch2rev);
+ this.groupBoxElevons.Controls.Add(this.CHK_elevonrev);
+ this.groupBoxElevons.Controls.Add(this.CHK_elevonch1rev);
+ this.groupBoxElevons.Location = new System.Drawing.Point(12, 356);
+ this.groupBoxElevons.Name = "groupBoxElevons";
+ this.groupBoxElevons.Size = new System.Drawing.Size(409, 42);
+ this.groupBoxElevons.TabIndex = 125;
+ this.groupBoxElevons.TabStop = false;
+ this.groupBoxElevons.Text = "Elevon Config";
+ //
+ // CHK_mixmode
+ //
+ this.CHK_mixmode.AutoSize = true;
+ this.CHK_mixmode.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_mixmode.Location = new System.Drawing.Point(13, 19);
+ this.CHK_mixmode.Name = "CHK_mixmode";
+ this.CHK_mixmode.Size = new System.Drawing.Size(64, 17);
+ this.CHK_mixmode.TabIndex = 107;
+ this.CHK_mixmode.Text = "Elevons";
+ this.CHK_mixmode.UseVisualStyleBackColor = true;
+ this.CHK_mixmode.CheckedChanged += new System.EventHandler(this.CHK_mixmode_CheckedChanged);
+ //
+ // CHK_elevonch2rev
+ //
+ this.CHK_elevonch2rev.AutoSize = true;
+ this.CHK_elevonch2rev.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_elevonch2rev.Location = new System.Drawing.Point(292, 19);
+ this.CHK_elevonch2rev.Name = "CHK_elevonch2rev";
+ this.CHK_elevonch2rev.Size = new System.Drawing.Size(111, 17);
+ this.CHK_elevonch2rev.TabIndex = 110;
+ this.CHK_elevonch2rev.Text = "Elevons CH2 Rev";
+ this.CHK_elevonch2rev.UseVisualStyleBackColor = true;
+ this.CHK_elevonch2rev.CheckedChanged += new System.EventHandler(this.CHK_elevonch2rev_CheckedChanged);
+ //
+ // CHK_elevonrev
+ //
+ this.CHK_elevonrev.AutoSize = true;
+ this.CHK_elevonrev.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_elevonrev.Location = new System.Drawing.Point(82, 19);
+ this.CHK_elevonrev.Name = "CHK_elevonrev";
+ this.CHK_elevonrev.Size = new System.Drawing.Size(87, 17);
+ this.CHK_elevonrev.TabIndex = 108;
+ this.CHK_elevonrev.Text = "Elevons Rev";
+ this.CHK_elevonrev.UseVisualStyleBackColor = true;
+ this.CHK_elevonrev.CheckedChanged += new System.EventHandler(this.CHK_elevonrev_CheckedChanged);
+ //
+ // CHK_elevonch1rev
+ //
+ this.CHK_elevonch1rev.AutoSize = true;
+ this.CHK_elevonch1rev.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_elevonch1rev.Location = new System.Drawing.Point(175, 19);
+ this.CHK_elevonch1rev.Name = "CHK_elevonch1rev";
+ this.CHK_elevonch1rev.Size = new System.Drawing.Size(111, 17);
+ this.CHK_elevonch1rev.TabIndex = 109;
+ this.CHK_elevonch1rev.Text = "Elevons CH1 Rev";
+ this.CHK_elevonch1rev.UseVisualStyleBackColor = true;
+ this.CHK_elevonch1rev.CheckedChanged += new System.EventHandler(this.CHK_elevonch1rev_CheckedChanged);
+ //
+ // CHK_revch3
+ //
+ this.CHK_revch3.AutoSize = true;
+ this.CHK_revch3.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_revch3.Location = new System.Drawing.Point(278, 161);
+ this.CHK_revch3.Name = "CHK_revch3";
+ this.CHK_revch3.Size = new System.Drawing.Size(66, 17);
+ this.CHK_revch3.TabIndex = 124;
+ this.CHK_revch3.Text = "Reverse";
+ this.CHK_revch3.UseVisualStyleBackColor = true;
+ this.CHK_revch3.CheckedChanged += new System.EventHandler(this.CHK_revch3_CheckedChanged);
+ //
+ // CHK_revch4
+ //
+ this.CHK_revch4.AutoSize = true;
+ this.CHK_revch4.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_revch4.Location = new System.Drawing.Point(306, 313);
+ this.CHK_revch4.Name = "CHK_revch4";
+ this.CHK_revch4.Size = new System.Drawing.Size(66, 17);
+ this.CHK_revch4.TabIndex = 123;
+ this.CHK_revch4.Text = "Reverse";
+ this.CHK_revch4.UseVisualStyleBackColor = true;
+ this.CHK_revch4.CheckedChanged += new System.EventHandler(this.CHK_revch4_CheckedChanged);
+ //
+ // CHK_revch2
+ //
+ this.CHK_revch2.AutoSize = true;
+ this.CHK_revch2.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_revch2.Location = new System.Drawing.Point(62, 161);
+ this.CHK_revch2.Name = "CHK_revch2";
+ this.CHK_revch2.Size = new System.Drawing.Size(66, 17);
+ this.CHK_revch2.TabIndex = 122;
+ this.CHK_revch2.Text = "Reverse";
+ this.CHK_revch2.UseVisualStyleBackColor = true;
+ this.CHK_revch2.CheckedChanged += new System.EventHandler(this.CHK_revch2_CheckedChanged);
+ //
+ // CHK_revch1
+ //
+ this.CHK_revch1.AutoSize = true;
+ this.CHK_revch1.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CHK_revch1.Location = new System.Drawing.Point(306, 19);
+ this.CHK_revch1.Name = "CHK_revch1";
+ this.CHK_revch1.Size = new System.Drawing.Size(66, 17);
+ this.CHK_revch1.TabIndex = 121;
+ this.CHK_revch1.Text = "Reverse";
+ this.CHK_revch1.UseVisualStyleBackColor = true;
+ this.CHK_revch1.CheckedChanged += new System.EventHandler(this.CHK_revch1_CheckedChanged);
+ //
+ // BUT_Calibrateradio
+ //
+ this.BUT_Calibrateradio.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_Calibrateradio.Location = new System.Drawing.Point(473, 347);
+ this.BUT_Calibrateradio.Name = "BUT_Calibrateradio";
+ this.BUT_Calibrateradio.Size = new System.Drawing.Size(134, 23);
+ this.BUT_Calibrateradio.TabIndex = 120;
+ this.BUT_Calibrateradio.Text = "Calibrate Radio";
+ this.BUT_Calibrateradio.UseVisualStyleBackColor = true;
+ this.BUT_Calibrateradio.Click += new System.EventHandler(this.BUT_Calibrateradio_Click);
+ //
+ // BAR8
+ //
+ this.BAR8.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+ this.BAR8.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+ this.BAR8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch8in", true));
+ this.BAR8.Label = "Radio 8";
+ this.BAR8.Location = new System.Drawing.Point(437, 247);
+ this.BAR8.Maximum = 2200;
+ this.BAR8.maxline = 0;
+ this.BAR8.Minimum = 800;
+ this.BAR8.minline = 0;
+ this.BAR8.Name = "BAR8";
+ this.BAR8.Size = new System.Drawing.Size(170, 25);
+ this.BAR8.TabIndex = 119;
+ this.BAR8.Value = 1500;
+ this.BAR8.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+ //
+ // BAR7
+ //
+ this.BAR7.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+ this.BAR7.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+ this.BAR7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch7in", true));
+ this.BAR7.Label = "Radio 7";
+ this.BAR7.Location = new System.Drawing.Point(437, 192);
+ this.BAR7.Maximum = 2200;
+ this.BAR7.maxline = 0;
+ this.BAR7.Minimum = 800;
+ this.BAR7.minline = 0;
+ this.BAR7.Name = "BAR7";
+ this.BAR7.Size = new System.Drawing.Size(170, 25);
+ this.BAR7.TabIndex = 118;
+ this.BAR7.Value = 1500;
+ this.BAR7.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+ //
+ // BAR6
+ //
+ this.BAR6.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+ this.BAR6.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+ this.BAR6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch6in", true));
+ this.BAR6.Label = "Radio 6";
+ this.BAR6.Location = new System.Drawing.Point(437, 137);
+ this.BAR6.Maximum = 2200;
+ this.BAR6.maxline = 0;
+ this.BAR6.Minimum = 800;
+ this.BAR6.minline = 0;
+ this.BAR6.Name = "BAR6";
+ this.BAR6.Size = new System.Drawing.Size(170, 25);
+ this.BAR6.TabIndex = 117;
+ this.BAR6.Value = 1500;
+ this.BAR6.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+ //
+ // BAR5
+ //
+ this.BAR5.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+ this.BAR5.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+ this.BAR5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch5in", true));
+ this.BAR5.Label = "Radio 5";
+ this.BAR5.Location = new System.Drawing.Point(437, 82);
+ this.BAR5.Maximum = 2200;
+ this.BAR5.maxline = 0;
+ this.BAR5.Minimum = 800;
+ this.BAR5.minline = 0;
+ this.BAR5.Name = "BAR5";
+ this.BAR5.Size = new System.Drawing.Size(170, 25);
+ this.BAR5.TabIndex = 116;
+ this.BAR5.Value = 1500;
+ this.BAR5.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+ //
+ // BARpitch
+ //
+ this.BARpitch.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+ this.BARpitch.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+ this.BARpitch.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch2in", true));
+ this.BARpitch.Label = "Pitch";
+ this.BARpitch.Location = new System.Drawing.Point(134, 64);
+ this.BARpitch.Maximum = 2200;
+ this.BARpitch.maxline = 0;
+ this.BARpitch.Minimum = 800;
+ this.BARpitch.minline = 0;
+ this.BARpitch.Name = "BARpitch";
+ this.BARpitch.Size = new System.Drawing.Size(47, 211);
+ this.BARpitch.TabIndex = 115;
+ this.BARpitch.Value = 1500;
+ this.BARpitch.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+ //
+ // BARthrottle
+ //
+ this.BARthrottle.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
+ this.BARthrottle.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+ this.BARthrottle.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true));
+ this.BARthrottle.Label = "Throttle";
+ this.BARthrottle.Location = new System.Drawing.Point(350, 64);
+ this.BARthrottle.Maximum = 2200;
+ this.BARthrottle.maxline = 0;
+ this.BARthrottle.Minimum = 800;
+ this.BARthrottle.minline = 0;
+ this.BARthrottle.Name = "BARthrottle";
+ this.BARthrottle.Size = new System.Drawing.Size(47, 211);
+ this.BARthrottle.TabIndex = 114;
+ this.BARthrottle.Value = 1000;
+ this.BARthrottle.ValueColor = System.Drawing.Color.Magenta;
+ //
+ // BARyaw
+ //
+ this.BARyaw.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+ this.BARyaw.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+ this.BARyaw.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true));
+ this.BARyaw.Label = "Yaw";
+ this.BARyaw.Location = new System.Drawing.Point(12, 307);
+ this.BARyaw.Maximum = 2200;
+ this.BARyaw.maxline = 0;
+ this.BARyaw.Minimum = 800;
+ this.BARyaw.minline = 0;
+ this.BARyaw.Name = "BARyaw";
+ this.BARyaw.Size = new System.Drawing.Size(288, 23);
+ this.BARyaw.TabIndex = 113;
+ this.BARyaw.Value = 1500;
+ this.BARyaw.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+ //
+ // BARroll
+ //
+ this.BARroll.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+ this.BARroll.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+ this.BARroll.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch1in", true));
+ this.BARroll.Label = "Roll";
+ this.BARroll.Location = new System.Drawing.Point(12, 13);
+ this.BARroll.Maximum = 2200;
+ this.BARroll.maxline = 0;
+ this.BARroll.Minimum = 800;
+ this.BARroll.minline = 0;
+ this.BARroll.Name = "BARroll";
+ this.BARroll.Size = new System.Drawing.Size(288, 23);
+ this.BARroll.TabIndex = 112;
+ this.BARroll.Value = 1500;
+ this.BARroll.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+ //
+ // currentStateBindingSource
+ //
+ this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState);
+ //
+ // ConfigRadioInput
+ //
+ this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+ this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+ this.Controls.Add(this.groupBoxElevons);
+ this.Controls.Add(this.CHK_revch3);
+ this.Controls.Add(this.CHK_revch4);
+ this.Controls.Add(this.CHK_revch2);
+ this.Controls.Add(this.CHK_revch1);
+ this.Controls.Add(this.BUT_Calibrateradio);
+ this.Controls.Add(this.BAR8);
+ this.Controls.Add(this.BAR7);
+ this.Controls.Add(this.BAR6);
+ this.Controls.Add(this.BAR5);
+ this.Controls.Add(this.BARpitch);
+ this.Controls.Add(this.BARthrottle);
+ this.Controls.Add(this.BARyaw);
+ this.Controls.Add(this.BARroll);
+ this.Name = "ConfigRadioInput";
+ this.Size = new System.Drawing.Size(628, 406);
+ this.Load += new System.EventHandler(this.ConfigRadioInput_Load);
+ this.groupBoxElevons.ResumeLayout(false);
+ this.groupBoxElevons.PerformLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
+ this.ResumeLayout(false);
+ this.PerformLayout();
+
+ }
+
+ #endregion
+
+ private System.Windows.Forms.GroupBox groupBoxElevons;
+ private System.Windows.Forms.CheckBox CHK_mixmode;
+ private System.Windows.Forms.CheckBox CHK_elevonch2rev;
+ private System.Windows.Forms.CheckBox CHK_elevonrev;
+ private System.Windows.Forms.CheckBox CHK_elevonch1rev;
+ private System.Windows.Forms.CheckBox CHK_revch3;
+ private System.Windows.Forms.CheckBox CHK_revch4;
+ private System.Windows.Forms.CheckBox CHK_revch2;
+ private System.Windows.Forms.CheckBox CHK_revch1;
+ private MyButton BUT_Calibrateradio;
+ private HorizontalProgressBar2 BAR8;
+ private HorizontalProgressBar2 BAR7;
+ private HorizontalProgressBar2 BAR6;
+ private HorizontalProgressBar2 BAR5;
+ private VerticalProgressBar2 BARpitch;
+ private VerticalProgressBar2 BARthrottle;
+ private HorizontalProgressBar2 BARyaw;
+ private HorizontalProgressBar2 BARroll;
+ private System.Windows.Forms.BindingSource currentStateBindingSource;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs
new file mode 100644
index 0000000000..1be32e8e81
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs
@@ -0,0 +1,357 @@
+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.GCSViews.ConfigurationView
+{
+ public partial class ConfigRadioInput : UserControl
+ {
+ bool startup = false;
+ bool run = false;
+
+ float[] rcmin = new float[8];
+ float[] rcmax = new float[8];
+ float[] rctrim = new float[8];
+
+ Timer timer = new Timer();
+
+ public ConfigRadioInput()
+ {
+ InitializeComponent();
+
+ // setup rc calib extents
+ for (int a = 0; a < rcmin.Length; a++)
+ {
+ rcmin[a] = 3000;
+ rcmax[a] = 0;
+ rctrim[a] = 1500;
+ }
+
+ // setup rc update
+ timer.Tick += new EventHandler(timer_Tick);
+
+ timer.Enabled = true;
+ timer.Interval = 100;
+ timer.Start();
+ }
+
+ void timer_Tick(object sender, EventArgs e)
+ {
+ // update all linked controls - 10hz
+ try
+ {
+ MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
+ }
+ catch { }
+ }
+
+ private void ConfigRadioInput_Load(object sender, EventArgs e)
+ {
+ startup = true;
+
+ if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+ {
+ groupBoxElevons.Visible = false;
+ }
+ else
+ {
+ try
+ {
+ CHK_mixmode.Checked = MainV2.comPort.param["ELEVON_MIXING"].ToString() == "1";
+ CHK_elevonrev.Checked = MainV2.comPort.param["ELEVON_REVERSE"].ToString() == "1";
+ CHK_elevonch1rev.Checked = MainV2.comPort.param["ELEVON_CH1_REV"].ToString() == "1";
+ CHK_elevonch2rev.Checked = MainV2.comPort.param["ELEVON_CH2_REV"].ToString() == "1";
+ }
+ catch { } // this will fail on arducopter
+ }
+ try
+ {
+ CHK_revch1.Checked = MainV2.comPort.param["RC1_REV"].ToString() == "-1";
+ CHK_revch2.Checked = MainV2.comPort.param["RC2_REV"].ToString() == "-1";
+ 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()); }
+ startup = false;
+ }
+
+ private void BUT_Calibrateradio_Click(object sender, EventArgs e)
+ {
+ if (run)
+ {
+ BUT_Calibrateradio.Text = "Completed";
+ run = false;
+ return;
+ }
+
+ CustomMessageBox.Show("Ensure your transmitter is on and receiver is powered and connected\nEnsure your motor does not have power/no props!!!");
+
+ byte oldrc = MainV2.cs.raterc;
+ byte oldatt = MainV2.cs.rateattitude;
+ byte oldpos = MainV2.cs.rateposition;
+ byte oldstatus = MainV2.cs.ratestatus;
+
+ MainV2.cs.raterc = 10;
+ MainV2.cs.rateattitude = 0;
+ MainV2.cs.rateposition = 0;
+ MainV2.cs.ratestatus = 0;
+
+ try
+ {
+
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, 10);
+
+ }
+ catch { }
+
+ BUT_Calibrateradio.Text = "Click when Done";
+
+ run = true;
+
+
+ while (run)
+ {
+ Application.DoEvents();
+
+ System.Threading.Thread.Sleep(5);
+
+ MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
+
+ // check for non 0 values
+ if (MainV2.cs.ch1in > 800 && MainV2.cs.ch1in < 2200)
+ {
+ rcmin[0] = Math.Min(rcmin[0], MainV2.cs.ch1in);
+ rcmax[0] = Math.Max(rcmax[0], MainV2.cs.ch1in);
+
+ rcmin[1] = Math.Min(rcmin[1], MainV2.cs.ch2in);
+ rcmax[1] = Math.Max(rcmax[1], MainV2.cs.ch2in);
+
+ rcmin[2] = Math.Min(rcmin[2], MainV2.cs.ch3in);
+ rcmax[2] = Math.Max(rcmax[2], MainV2.cs.ch3in);
+
+ rcmin[3] = Math.Min(rcmin[3], MainV2.cs.ch4in);
+ rcmax[3] = Math.Max(rcmax[3], MainV2.cs.ch4in);
+
+ rcmin[4] = Math.Min(rcmin[4], MainV2.cs.ch5in);
+ rcmax[4] = Math.Max(rcmax[4], MainV2.cs.ch5in);
+
+ rcmin[5] = Math.Min(rcmin[5], MainV2.cs.ch6in);
+ rcmax[5] = Math.Max(rcmax[5], MainV2.cs.ch6in);
+
+ rcmin[6] = Math.Min(rcmin[6], MainV2.cs.ch7in);
+ rcmax[6] = Math.Max(rcmax[6], MainV2.cs.ch7in);
+
+ rcmin[7] = Math.Min(rcmin[7], MainV2.cs.ch8in);
+ rcmax[7] = Math.Max(rcmax[7], MainV2.cs.ch8in);
+
+ BARroll.minline = (int)rcmin[0];
+ BARroll.maxline = (int)rcmax[0];
+
+ BARpitch.minline = (int)rcmin[1];
+ BARpitch.maxline = (int)rcmax[1];
+
+ BARthrottle.minline = (int)rcmin[2];
+ BARthrottle.maxline = (int)rcmax[2];
+
+ BARyaw.minline = (int)rcmin[3];
+ BARyaw.maxline = (int)rcmax[3];
+
+ BAR5.minline = (int)rcmin[4];
+ BAR5.maxline = (int)rcmax[4];
+
+ BAR6.minline = (int)rcmin[5];
+ BAR6.maxline = (int)rcmax[5];
+
+ BAR7.minline = (int)rcmin[6];
+ BAR7.maxline = (int)rcmax[6];
+
+ BAR8.minline = (int)rcmin[7];
+ BAR8.maxline = (int)rcmax[7];
+
+ }
+ }
+
+ CustomMessageBox.Show("Ensure all your sticks are centered and throttle is down, and click ok to continue");
+
+ MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
+
+ rctrim[0] = MainV2.cs.ch1in;
+ rctrim[1] = MainV2.cs.ch2in;
+ rctrim[2] = MainV2.cs.ch3in;
+ rctrim[3] = MainV2.cs.ch4in;
+ rctrim[4] = MainV2.cs.ch5in;
+ rctrim[5] = MainV2.cs.ch6in;
+ rctrim[6] = MainV2.cs.ch7in;
+ rctrim[7] = MainV2.cs.ch8in;
+
+ string data = "---------------\n";
+
+ for (int a = 0; a < 8; a++)
+ {
+ // we want these to save no matter what
+ BUT_Calibrateradio.Text = "Saving";
+ try
+ {
+ if (rcmin[a] != rcmax[a])
+ {
+ MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_MIN", rcmin[a]);
+ MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_MAX", rcmax[a]);
+ }
+ if (rctrim[a] < 1195 || rctrim[a] > 1205)
+ MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_TRIM", rctrim[a]);
+ }
+ catch { CustomMessageBox.Show("Failed to set Channel " + (a + 1).ToString()); }
+
+ data = data + "CH" + (a + 1) + " " + rcmin[a] + " | " + rcmax[a] + "\n";
+ }
+
+ MainV2.cs.raterc = oldrc;
+ MainV2.cs.rateattitude = oldatt;
+ MainV2.cs.rateposition = oldpos;
+ MainV2.cs.ratestatus = oldstatus;
+
+ try
+ {
+
+ MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, oldrc);
+
+ }
+ catch { }
+
+ CustomMessageBox.Show("Here are the detected radio options\nNOTE Channels not connected are displayed as 1500 +-2\nNormal values are around 1100 | 1900\nChannel:Min | Max \n" + data, "Radio");
+
+ BUT_Calibrateradio.Text = "Completed";
+ }
+
+ private void CHK_mixmode_CheckedChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ try
+ {
+ if (MainV2.comPort.param["ELEVON_MIXING"] == null)
+ {
+ CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ }
+ else
+ {
+ MainV2.comPort.setParam("ELEVON_MIXING", ((CheckBox)sender).Checked == true ? 1 : 0);
+ }
+ }
+ catch { CustomMessageBox.Show("Set ELEVON_MIXING Failed"); }
+ }
+
+ private void CHK_elevonrev_CheckedChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ try
+ {
+ if (MainV2.comPort.param["ELEVON_REVERSE"] == null)
+ {
+ CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ }
+ else
+ {
+ MainV2.comPort.setParam("ELEVON_REVERSE", ((CheckBox)sender).Checked == true ? 1 : 0);
+ }
+ }
+ catch { CustomMessageBox.Show("Set ELEVON_REVERSE Failed"); }
+ }
+
+ private void CHK_elevonch1rev_CheckedChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ try
+ {
+ if (MainV2.comPort.param["ELEVON_CH1_REV"] == null)
+ {
+ CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ }
+ else
+ {
+ MainV2.comPort.setParam("ELEVON_CH1_REV", ((CheckBox)sender).Checked == true ? 1 : 0);
+ }
+ }
+ catch { CustomMessageBox.Show("Set ELEVON_CH1_REV Failed"); }
+ }
+
+ private void CHK_elevonch2rev_CheckedChanged(object sender, EventArgs e)
+ {
+ if (startup)
+ return;
+ try
+ {
+ if (MainV2.comPort.param["ELEVON_CH2_REV"] == null)
+ {
+ CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+ }
+ else
+ {
+ MainV2.comPort.setParam("ELEVON_CH2_REV", ((CheckBox)sender).Checked == true ? 1 : 0);
+ }
+ }
+ catch { CustomMessageBox.Show("Set ELEVON_CH2_REV Failed"); }
+ }
+
+ private void CHK_revch1_CheckedChanged(object sender, EventArgs e)
+ {
+ reverseChannel("RC1_REV", ((CheckBox)sender).Checked, BARroll);
+ }
+
+ private void CHK_revch2_CheckedChanged(object sender, EventArgs e)
+ {
+ reverseChannel("RC2_REV", ((CheckBox)sender).Checked, BARpitch);
+ }
+
+ private void CHK_revch3_CheckedChanged(object sender, EventArgs e)
+ {
+ reverseChannel("RC3_REV", ((CheckBox)sender).Checked, BARthrottle);
+ }
+
+ private void CHK_revch4_CheckedChanged(object sender, EventArgs e)
+ {
+ reverseChannel("RC4_REV", ((CheckBox)sender).Checked, BARyaw);
+ }
+
+ void reverseChannel(string name, bool normalreverse, Control progressbar)
+ {
+ if (normalreverse == true)
+ {
+ ((HorizontalProgressBar2)progressbar).reverse = true;
+ ((HorizontalProgressBar2)progressbar).BackgroundColor = Color.FromArgb(148, 193, 31);
+ ((HorizontalProgressBar2)progressbar).ValueColor = Color.FromArgb(0x43, 0x44, 0x45);
+ }
+ else
+ {
+ ((HorizontalProgressBar2)progressbar).reverse = false;
+ ((HorizontalProgressBar2)progressbar).BackgroundColor = Color.FromArgb(0x43, 0x44, 0x45);
+ ((HorizontalProgressBar2)progressbar).ValueColor = Color.FromArgb(148, 193, 31);
+ }
+
+ if (startup)
+ return;
+ if (MainV2.comPort.param["SWITCH_ENABLE"] != null && (float)MainV2.comPort.param["SWITCH_ENABLE"] == 1)
+ {
+ try
+ {
+ MainV2.comPort.setParam("SWITCH_ENABLE", 0);
+ CustomMessageBox.Show("Disabled Dip Switchs");
+ }
+ catch { CustomMessageBox.Show("Error Disableing Dip Switch"); }
+ }
+ try
+ {
+ int i = normalreverse == false ? 1 : -1;
+ MainV2.comPort.setParam(name, i);
+ }
+ catch { CustomMessageBox.Show("Error Reversing"); }
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx
new file mode 100644
index 0000000000..6791def873
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx
@@ -0,0 +1,123 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 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
+
+
+ 17, 17
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
new file mode 100644
index 0000000000..7887cd29c9
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
@@ -0,0 +1,205 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class ConfigRawParams
+ {
+ ///
+ /// 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()
+ {
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
+ this.BUT_compare = new ArdupilotMega.MyButton();
+ this.BUT_rerequestparams = new ArdupilotMega.MyButton();
+ this.BUT_writePIDS = new ArdupilotMega.MyButton();
+ this.BUT_save = new ArdupilotMega.MyButton();
+ this.BUT_load = new ArdupilotMega.MyButton();
+ this.Params = new System.Windows.Forms.DataGridView();
+ this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
+ this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn();
+ this.Default = new System.Windows.Forms.DataGridViewTextBoxColumn();
+ this.mavScale = new System.Windows.Forms.DataGridViewTextBoxColumn();
+ this.RawValue = new System.Windows.Forms.DataGridViewTextBoxColumn();
+ ((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit();
+ this.SuspendLayout();
+ //
+ // BUT_compare
+ //
+ this.BUT_compare.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_compare.Location = new System.Drawing.Point(341, 119);
+ this.BUT_compare.Name = "BUT_compare";
+ this.BUT_compare.Size = new System.Drawing.Size(103, 19);
+ this.BUT_compare.TabIndex = 72;
+ this.BUT_compare.Text = "Compare Params";
+ this.BUT_compare.UseVisualStyleBackColor = true;
+ this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click);
+ //
+ // BUT_rerequestparams
+ //
+ this.BUT_rerequestparams.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_rerequestparams.Location = new System.Drawing.Point(341, 94);
+ this.BUT_rerequestparams.Name = "BUT_rerequestparams";
+ this.BUT_rerequestparams.Size = new System.Drawing.Size(103, 19);
+ this.BUT_rerequestparams.TabIndex = 67;
+ this.BUT_rerequestparams.Text = "Refresh Params";
+ this.BUT_rerequestparams.UseVisualStyleBackColor = true;
+ this.BUT_rerequestparams.Click += new System.EventHandler(this.BUT_rerequestparams_Click);
+ //
+ // BUT_writePIDS
+ //
+ this.BUT_writePIDS.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_writePIDS.Location = new System.Drawing.Point(341, 69);
+ this.BUT_writePIDS.Name = "BUT_writePIDS";
+ this.BUT_writePIDS.Size = new System.Drawing.Size(103, 19);
+ this.BUT_writePIDS.TabIndex = 69;
+ this.BUT_writePIDS.Text = "Write Params";
+ this.BUT_writePIDS.UseVisualStyleBackColor = true;
+ this.BUT_writePIDS.Click += new System.EventHandler(this.BUT_writePIDS_Click);
+ //
+ // BUT_save
+ //
+ this.BUT_save.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_save.Location = new System.Drawing.Point(341, 35);
+ this.BUT_save.Margin = new System.Windows.Forms.Padding(0);
+ this.BUT_save.Name = "BUT_save";
+ this.BUT_save.Size = new System.Drawing.Size(104, 19);
+ this.BUT_save.TabIndex = 70;
+ this.BUT_save.Text = "Save";
+ this.BUT_save.UseVisualStyleBackColor = true;
+ this.BUT_save.Click += new System.EventHandler(this.BUT_save_Click);
+ //
+ // BUT_load
+ //
+ this.BUT_load.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_load.Location = new System.Drawing.Point(341, 7);
+ this.BUT_load.Margin = new System.Windows.Forms.Padding(0);
+ this.BUT_load.Name = "BUT_load";
+ this.BUT_load.Size = new System.Drawing.Size(104, 19);
+ this.BUT_load.TabIndex = 71;
+ this.BUT_load.Text = "Load";
+ this.BUT_load.UseVisualStyleBackColor = true;
+ this.BUT_load.Click += new System.EventHandler(this.BUT_load_Click);
+ //
+ // Params
+ //
+ this.Params.AllowUserToAddRows = false;
+ this.Params.AllowUserToDeleteRows = false;
+ this.Params.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom)
+ | System.Windows.Forms.AnchorStyles.Left)));
+ dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
+ dataGridViewCellStyle1.BackColor = System.Drawing.Color.Maroon;
+ dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
+ dataGridViewCellStyle1.ForeColor = System.Drawing.Color.White;
+ dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight;
+ dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
+ dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
+ this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1;
+ this.Params.ColumnHeadersHeightSizeMode = System.Windows.Forms.DataGridViewColumnHeadersHeightSizeMode.AutoSize;
+ this.Params.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
+ this.Command,
+ this.Value,
+ this.Default,
+ this.mavScale,
+ this.RawValue});
+ this.Params.Location = new System.Drawing.Point(14, 3);
+ this.Params.Name = "Params";
+ dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
+ dataGridViewCellStyle2.BackColor = System.Drawing.SystemColors.ActiveCaption;
+ dataGridViewCellStyle2.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
+ dataGridViewCellStyle2.ForeColor = System.Drawing.SystemColors.WindowText;
+ dataGridViewCellStyle2.SelectionBackColor = System.Drawing.SystemColors.Highlight;
+ dataGridViewCellStyle2.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
+ dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
+ this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2;
+ this.Params.RowHeadersVisible = false;
+ this.Params.RowHeadersWidth = 150;
+ this.Params.Size = new System.Drawing.Size(321, 302);
+ this.Params.TabIndex = 68;
+ //
+ // Command
+ //
+ this.Command.HeaderText = "Command";
+ this.Command.Name = "Command";
+ this.Command.ReadOnly = true;
+ this.Command.Width = 150;
+ //
+ // Value
+ //
+ this.Value.HeaderText = "Value";
+ this.Value.Name = "Value";
+ this.Value.Width = 80;
+ //
+ // Default
+ //
+ this.Default.HeaderText = "Default";
+ this.Default.Name = "Default";
+ this.Default.Visible = false;
+ //
+ // mavScale
+ //
+ this.mavScale.HeaderText = "mavScale";
+ this.mavScale.Name = "mavScale";
+ this.mavScale.Visible = false;
+ //
+ // RawValue
+ //
+ this.RawValue.HeaderText = "RawValue";
+ this.RawValue.Name = "RawValue";
+ this.RawValue.Visible = false;
+ //
+ // ConfigRawParams
+ //
+ this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+ this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+ this.Controls.Add(this.BUT_compare);
+ this.Controls.Add(this.BUT_rerequestparams);
+ this.Controls.Add(this.BUT_writePIDS);
+ this.Controls.Add(this.BUT_save);
+ this.Controls.Add(this.BUT_load);
+ this.Controls.Add(this.Params);
+ this.Name = "ConfigRawParams";
+ this.Size = new System.Drawing.Size(460, 305);
+ this.Load += new System.EventHandler(this.ConfigRawParams_Load);
+ this.ControlAdded += new System.Windows.Forms.ControlEventHandler(this.ConfigRawParams_ControlAdded);
+ this.ControlRemoved += new System.Windows.Forms.ControlEventHandler(this.ConfigRawParams_ControlRemoved);
+ ((System.ComponentModel.ISupportInitialize)(this.Params)).EndInit();
+ this.ResumeLayout(false);
+
+ }
+
+ #endregion
+
+ private MyButton BUT_compare;
+ private MyButton BUT_rerequestparams;
+ private MyButton BUT_writePIDS;
+ private MyButton BUT_save;
+ private MyButton BUT_load;
+ private System.Windows.Forms.DataGridView Params;
+ private System.Windows.Forms.DataGridViewTextBoxColumn Command;
+ private System.Windows.Forms.DataGridViewTextBoxColumn Value;
+ private System.Windows.Forms.DataGridViewTextBoxColumn Default;
+ private System.Windows.Forms.DataGridViewTextBoxColumn mavScale;
+ private System.Windows.Forms.DataGridViewTextBoxColumn RawValue;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
new file mode 100644
index 0000000000..5b2c7d1d82
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
@@ -0,0 +1,287 @@
+using System;
+using System.Collections;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.IO;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using log4net;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ public partial class ConfigRawParams : UserControl
+ {
+ private static readonly ILog log =
+ LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
+
+ // Changes made to the params between writing to the copter
+ readonly Hashtable _changes = new Hashtable();
+
+ // ?
+ internal bool startup = true;
+
+
+ public ConfigRawParams()
+ {
+ InitializeComponent();
+ }
+
+ Hashtable loadParamFile(string Filename)
+ {
+ Hashtable param = new Hashtable();
+
+ StreamReader sr = new StreamReader(Filename);
+ while (!sr.EndOfStream)
+ {
+ string line = sr.ReadLine();
+
+ if (line.Contains("NOTE:"))
+ CustomMessageBox.Show(line, "Saved Note");
+
+ if (line.StartsWith("#"))
+ continue;
+
+ string[] items = line.Split(new char[] { ' ', ',', '\t' }, StringSplitOptions.RemoveEmptyEntries);
+
+ if (items.Length != 2)
+ continue;
+
+ string name = items[0];
+ float value = float.Parse(items[1], new System.Globalization.CultureInfo("en-US"));
+
+ MAVLink.modifyParamForDisplay(true, name, ref value);
+
+ if (name == "SYSID_SW_MREV")
+ continue;
+ if (name == "WP_TOTAL")
+ continue;
+ if (name == "CMD_TOTAL")
+ continue;
+ if (name == "FENCE_TOTAL")
+ continue;
+ if (name == "SYS_NUM_RESETS")
+ continue;
+ if (name == "ARSPD_OFFSET")
+ continue;
+ if (name == "GND_ABS_PRESS")
+ continue;
+ if (name == "GND_TEMP")
+ continue;
+ if (name == "CMD_INDEX")
+ continue;
+ if (name == "LOG_LASTFILE")
+ continue;
+
+ param[name] = value;
+ }
+ sr.Close();
+
+ return param;
+ }
+
+ private void BUT_load_Click(object sender, EventArgs e)
+ {
+ var ofd = new OpenFileDialog
+ {
+ AddExtension = true,
+ DefaultExt = ".param",
+ RestoreDirectory = true,
+ Filter = "Param List|*.param;*.parm"
+ };
+ var dr = ofd.ShowDialog();
+
+ if (dr == DialogResult.OK)
+ {
+ Hashtable param2 = loadParamFile(ofd.FileName);
+
+ foreach (string name in param2.Keys)
+ {
+ string value = param2[name].ToString();
+ // set param table as well
+ foreach (DataGridViewRow row in Params.Rows)
+ {
+ if (name == "SYSID_SW_MREV")
+ continue;
+ if (name == "WP_TOTAL")
+ continue;
+ if (name == "CMD_TOTAL")
+ continue;
+ if (name == "FENCE_TOTAL")
+ continue;
+ if (name == "SYS_NUM_RESETS")
+ continue;
+ if (name == "ARSPD_OFFSET")
+ continue;
+ if (name == "GND_ABS_PRESS")
+ continue;
+ if (name == "GND_TEMP")
+ continue;
+ if (name == "CMD_INDEX")
+ continue;
+ if (name == "LOG_LASTFILE")
+ continue;
+ if (row.Cells[0].Value.ToString() == name)
+ {
+ if (row.Cells[1].Value.ToString() != value.ToString())
+ row.Cells[1].Value = value;
+ break;
+ }
+ }
+ }
+ }
+ }
+
+ private void BUT_save_Click(object sender, EventArgs e)
+ {
+ var sfd = new SaveFileDialog
+ {
+ AddExtension = true,
+ DefaultExt = ".param",
+ RestoreDirectory = true,
+ Filter = "Param List|*.param;*.parm"
+ };
+
+ var dr = sfd.ShowDialog();
+ if (dr == DialogResult.OK)
+ {
+ StreamWriter sw = new StreamWriter(sfd.OpenFile());
+ string input = DateTime.Now + " Frame : + | Arducopter Kit | Kit motors";
+ if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
+ {
+ input = DateTime.Now + " Plane: Skywalker";
+ }
+ Common.InputBox("Custom Note", "Enter your Notes/Frame Type etc", ref input);
+ if (input != "")
+ sw.WriteLine("NOTE: " + input.Replace(',', '|'));
+ foreach (DataGridViewRow row in Params.Rows)
+ {
+ float value = float.Parse(row.Cells[1].Value.ToString());
+
+ MAVLink.modifyParamForDisplay(false, row.Cells[0].Value.ToString(), ref value);
+
+ sw.WriteLine(row.Cells[0].Value.ToString() + "," + value.ToString(new System.Globalization.CultureInfo("en-US")));
+ }
+ sw.Close();
+ }
+ }
+
+ private void BUT_writePIDS_Click(object sender, EventArgs e)
+ {
+ var temp = (Hashtable)_changes.Clone();
+
+ foreach (string value in temp.Keys)
+ {
+ try
+ {
+ MainV2.comPort.setParam(value, (float)_changes[value]);
+
+ try
+ {
+ // set control as well
+ var textControls = this.Controls.Find(value, true);
+ if (textControls.Length > 0)
+ {
+ textControls[0].BackColor = Color.FromArgb(0x43, 0x44, 0x45);
+ }
+ }
+ catch
+ {
+
+ }
+
+ try
+ {
+ // set param table as well
+ foreach (DataGridViewRow row in Params.Rows)
+ {
+ if (row.Cells[0].Value.ToString() == value)
+ {
+ row.Cells[1].Style.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
+ _changes.Remove(value);
+ break;
+ }
+ }
+ }
+ catch { }
+
+ }
+ catch
+ {
+ CustomMessageBox.Show("Set " + value + " Failed");
+ }
+ }
+ }
+
+
+ private void BUT_compare_Click(object sender, EventArgs e)
+ {
+ Hashtable param2 = new Hashtable();
+
+ var ofd = new OpenFileDialog
+ {
+ AddExtension = true,
+ DefaultExt = ".param",
+ RestoreDirectory = true,
+ Filter = "Param List|*.param;*.parm"
+ };
+
+ var dr = ofd.ShowDialog();
+ if (dr == DialogResult.OK)
+ {
+ param2 = loadParamFile(ofd.FileName);
+
+ int fixme;
+ //var paramCompareForm = new ParamCompare((Form)this, MainV2.comPort.param, param2);
+
+ //ThemeManager.ApplyThemeTo(paramCompareForm);
+ //paramCompareForm.ShowDialog();
+ }
+ }
+
+
+ private void BUT_rerequestparams_Click(object sender, EventArgs e)
+ {
+ if (!MainV2.comPort.BaseStream.IsOpen)
+ return;
+
+ ((Control)sender).Enabled = false;
+
+ try
+ {
+ MainV2.comPort.getParamList();
+ }
+ catch (Exception ex)
+ {
+ log.Error("Exception getting param list", ex);
+ CustomMessageBox.Show("Error: getting param list");
+ }
+
+
+ ((Control)sender).Enabled = true;
+
+ startup = true;
+
+ // Todo: this populates or the combos etc and what not. This shoudl prob be a bsv button
+
+ }
+
+ private void ConfigRawParams_Load(object sender, EventArgs e)
+ {
+
+ }
+
+ private void ConfigRawParams_ControlRemoved(object sender, ControlEventArgs e)
+ {
+
+ }
+
+ private void ConfigRawParams_ControlAdded(object sender, ControlEventArgs e)
+ {
+
+ }
+
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx
new file mode 100644
index 0000000000..3267b69260
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx
@@ -0,0 +1,132 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 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
+
+
+ True
+
+
+ True
+
+
+ True
+
+
+ True
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs
new file mode 100644
index 0000000000..fd4b1fcd6c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs
@@ -0,0 +1,857 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class ConfigTradHeli
+ {
+ ///
+ /// 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.groupBox5 = new System.Windows.Forms.GroupBox();
+ this.H1_ENABLE = new System.Windows.Forms.RadioButton();
+ this.CCPM = new System.Windows.Forms.RadioButton();
+ this.BUT_swash_manual = new ArdupilotMega.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.GYR_ENABLE = new System.Windows.Forms.CheckBox();
+ this.GYR_GAIN = new System.Windows.Forms.TextBox();
+ this.BUT_HS4save = new ArdupilotMega.MyButton();
+ this.label21 = new System.Windows.Forms.Label();
+ this.COL_MIN = new System.Windows.Forms.TextBox();
+ this.groupBox1 = new System.Windows.Forms.GroupBox();
+ this.COL_MID = new System.Windows.Forms.TextBox();
+ this.COL_MAX = new System.Windows.Forms.TextBox();
+ this.BUT_0collective = new ArdupilotMega.MyButton();
+ this.groupBox2 = new System.Windows.Forms.GroupBox();
+ this.label24 = new System.Windows.Forms.Label();
+ this.HS4_MIN = new System.Windows.Forms.TextBox();
+ this.HS4_MAX = new System.Windows.Forms.TextBox();
+ this.label40 = new System.Windows.Forms.Label();
+ this.HS3_TRIM = new System.Windows.Forms.NumericUpDown();
+ this.HS2_TRIM = new System.Windows.Forms.NumericUpDown();
+ this.HS1_TRIM = new System.Windows.Forms.NumericUpDown();
+ this.label39 = new System.Windows.Forms.Label();
+ this.label38 = new System.Windows.Forms.Label();
+ this.label37 = new System.Windows.Forms.Label();
+ this.label36 = new System.Windows.Forms.Label();
+ this.label26 = new System.Windows.Forms.Label();
+ this.PIT_MAX = new System.Windows.Forms.TextBox();
+ this.label25 = new System.Windows.Forms.Label();
+ this.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();
+ this.label19 = new System.Windows.Forms.Label();
+ this.label18 = new System.Windows.Forms.Label();
+ this.SV3_POS = new System.Windows.Forms.TextBox();
+ this.SV2_POS = new System.Windows.Forms.TextBox();
+ this.SV1_POS = new System.Windows.Forms.TextBox();
+ this.HS3_REV = new System.Windows.Forms.CheckBox();
+ 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.HS3 = new ArdupilotMega.VerticalProgressBar2();
+ this.Gservoloc = new AGaugeApp.AGauge();
+ this.groupBox5.SuspendLayout();
+ this.groupBox3.SuspendLayout();
+ this.groupBox1.SuspendLayout();
+ this.groupBox2.SuspendLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).BeginInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).BeginInit();
+ this.SuspendLayout();
+ //
+ // groupBox5
+ //
+ this.groupBox5.Controls.Add(this.H1_ENABLE);
+ this.groupBox5.Controls.Add(this.CCPM);
+ this.groupBox5.Location = new System.Drawing.Point(257, 11);
+ this.groupBox5.Name = "groupBox5";
+ this.groupBox5.Size = new System.Drawing.Size(120, 43);
+ this.groupBox5.TabIndex = 169;
+ this.groupBox5.TabStop = false;
+ this.groupBox5.Text = "Swash Type";
+ //
+ // H1_ENABLE
+ //
+ this.H1_ENABLE.AutoSize = true;
+ this.H1_ENABLE.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.H1_ENABLE.Location = new System.Drawing.Point(67, 19);
+ this.H1_ENABLE.Name = "H1_ENABLE";
+ this.H1_ENABLE.Size = new System.Drawing.Size(39, 17);
+ this.H1_ENABLE.TabIndex = 137;
+ this.H1_ENABLE.TabStop = true;
+ this.H1_ENABLE.Text = "H1";
+ this.H1_ENABLE.UseVisualStyleBackColor = true;
+ //
+ // CCPM
+ //
+ this.CCPM.AutoSize = true;
+ this.CCPM.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.CCPM.Location = new System.Drawing.Point(6, 19);
+ this.CCPM.Name = "CCPM";
+ this.CCPM.Size = new System.Drawing.Size(55, 17);
+ this.CCPM.TabIndex = 136;
+ this.CCPM.TabStop = true;
+ this.CCPM.Text = "CCPM";
+ this.CCPM.UseVisualStyleBackColor = true;
+ //
+ // BUT_swash_manual
+ //
+ this.BUT_swash_manual.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_swash_manual.Location = new System.Drawing.Point(302, 83);
+ this.BUT_swash_manual.Name = "BUT_swash_manual";
+ this.BUT_swash_manual.Size = new System.Drawing.Size(69, 23);
+ this.BUT_swash_manual.TabIndex = 138;
+ this.BUT_swash_manual.Text = "Manual";
+ this.BUT_swash_manual.UseVisualStyleBackColor = true;
+ //
+ // label41
+ //
+ this.label41.AutoSize = true;
+ this.label41.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label41.Location = new System.Drawing.Point(19, 157);
+ this.label41.Name = "label41";
+ this.label41.Size = new System.Drawing.Size(40, 13);
+ this.label41.TabIndex = 122;
+ this.label41.Text = "Bottom";
+ //
+ // groupBox3
+ //
+ this.groupBox3.Controls.Add(this.label46);
+ this.groupBox3.Controls.Add(this.label45);
+ this.groupBox3.Controls.Add(this.GYR_ENABLE);
+ this.groupBox3.Controls.Add(this.GYR_GAIN);
+ this.groupBox3.Location = new System.Drawing.Point(437, 314);
+ this.groupBox3.Name = "groupBox3";
+ this.groupBox3.Size = new System.Drawing.Size(101, 63);
+ this.groupBox3.TabIndex = 168;
+ this.groupBox3.TabStop = false;
+ this.groupBox3.Text = "Gyro";
+ //
+ // label46
+ //
+ this.label46.AutoSize = true;
+ this.label46.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label46.Location = new System.Drawing.Point(6, 38);
+ this.label46.Name = "label46";
+ this.label46.Size = new System.Drawing.Size(29, 13);
+ this.label46.TabIndex = 137;
+ this.label46.Text = "Gain";
+ //
+ // label45
+ //
+ this.label45.AutoSize = true;
+ this.label45.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label45.Location = new System.Drawing.Point(6, 19);
+ this.label45.Name = "label45";
+ this.label45.Size = new System.Drawing.Size(40, 13);
+ this.label45.TabIndex = 136;
+ this.label45.Text = "Enable";
+ //
+ // GYR_ENABLE
+ //
+ this.GYR_ENABLE.AutoSize = true;
+ this.GYR_ENABLE.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.GYR_ENABLE.Location = new System.Drawing.Point(57, 19);
+ this.GYR_ENABLE.Name = "GYR_ENABLE";
+ this.GYR_ENABLE.Size = new System.Drawing.Size(15, 14);
+ this.GYR_ENABLE.TabIndex = 118;
+ this.GYR_ENABLE.UseVisualStyleBackColor = true;
+ //
+ // GYR_GAIN
+ //
+ this.GYR_GAIN.Location = new System.Drawing.Point(41, 35);
+ this.GYR_GAIN.Name = "GYR_GAIN";
+ this.GYR_GAIN.Size = new System.Drawing.Size(47, 20);
+ this.GYR_GAIN.TabIndex = 119;
+ this.GYR_GAIN.Text = "1000";
+ //
+ // BUT_HS4save
+ //
+ this.BUT_HS4save.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_HS4save.Location = new System.Drawing.Point(483, 174);
+ this.BUT_HS4save.Name = "BUT_HS4save";
+ this.BUT_HS4save.Size = new System.Drawing.Size(69, 23);
+ this.BUT_HS4save.TabIndex = 167;
+ this.BUT_HS4save.Text = "Manual";
+ this.BUT_HS4save.UseVisualStyleBackColor = true;
+ //
+ // label21
+ //
+ this.label21.AutoSize = true;
+ this.label21.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label21.Location = new System.Drawing.Point(24, 28);
+ this.label21.Name = "label21";
+ this.label21.Size = new System.Drawing.Size(26, 13);
+ this.label21.TabIndex = 120;
+ this.label21.Text = "Top";
+ //
+ // COL_MIN
+ //
+ this.COL_MIN.Enabled = false;
+ this.COL_MIN.Location = new System.Drawing.Point(18, 173);
+ this.COL_MIN.Name = "COL_MIN";
+ this.COL_MIN.Size = new System.Drawing.Size(43, 20);
+ this.COL_MIN.TabIndex = 119;
+ this.COL_MIN.Text = "1500";
+ //
+ // groupBox1
+ //
+ this.groupBox1.Controls.Add(this.label41);
+ this.groupBox1.Controls.Add(this.label21);
+ this.groupBox1.Controls.Add(this.COL_MIN);
+ this.groupBox1.Controls.Add(this.COL_MID);
+ this.groupBox1.Controls.Add(this.COL_MAX);
+ this.groupBox1.Controls.Add(this.BUT_0collective);
+ this.groupBox1.Location = new System.Drawing.Point(297, 95);
+ this.groupBox1.Name = "groupBox1";
+ this.groupBox1.Size = new System.Drawing.Size(80, 209);
+ this.groupBox1.TabIndex = 165;
+ this.groupBox1.TabStop = false;
+ //
+ // COL_MID
+ //
+ this.COL_MID.Enabled = false;
+ this.COL_MID.Location = new System.Drawing.Point(17, 117);
+ this.COL_MID.Name = "COL_MID";
+ this.COL_MID.Size = new System.Drawing.Size(44, 20);
+ this.COL_MID.TabIndex = 117;
+ this.COL_MID.Text = "1500";
+ //
+ // COL_MAX
+ //
+ this.COL_MAX.Enabled = false;
+ this.COL_MAX.Location = new System.Drawing.Point(18, 45);
+ this.COL_MAX.Name = "COL_MAX";
+ this.COL_MAX.Size = new System.Drawing.Size(43, 20);
+ this.COL_MAX.TabIndex = 115;
+ this.COL_MAX.Text = "1500";
+ //
+ // BUT_0collective
+ //
+ this.BUT_0collective.Enabled = false;
+ this.BUT_0collective.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.BUT_0collective.Location = new System.Drawing.Point(11, 89);
+ this.BUT_0collective.Name = "BUT_0collective";
+ this.BUT_0collective.Size = new System.Drawing.Size(58, 23);
+ this.BUT_0collective.TabIndex = 110;
+ this.BUT_0collective.Text = "Zero";
+ this.BUT_0collective.UseVisualStyleBackColor = true;
+ //
+ // groupBox2
+ //
+ this.groupBox2.Controls.Add(this.label24);
+ this.groupBox2.Controls.Add(this.HS4_MIN);
+ this.groupBox2.Controls.Add(this.HS4_MAX);
+ this.groupBox2.Controls.Add(this.label40);
+ this.groupBox2.Location = new System.Drawing.Point(437, 186);
+ this.groupBox2.Name = "groupBox2";
+ this.groupBox2.Size = new System.Drawing.Size(169, 78);
+ this.groupBox2.TabIndex = 166;
+ this.groupBox2.TabStop = false;
+ //
+ // label24
+ //
+ this.label24.AutoSize = true;
+ this.label24.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label24.Location = new System.Drawing.Point(112, 23);
+ this.label24.Name = "label24";
+ this.label24.Size = new System.Drawing.Size(27, 13);
+ this.label24.TabIndex = 135;
+ this.label24.Text = "Max";
+ //
+ // HS4_MIN
+ //
+ this.HS4_MIN.Enabled = false;
+ this.HS4_MIN.Location = new System.Drawing.Point(21, 40);
+ this.HS4_MIN.Name = "HS4_MIN";
+ this.HS4_MIN.Size = new System.Drawing.Size(43, 20);
+ this.HS4_MIN.TabIndex = 132;
+ this.HS4_MIN.Text = "1500";
+ //
+ // HS4_MAX
+ //
+ this.HS4_MAX.Enabled = false;
+ this.HS4_MAX.Location = new System.Drawing.Point(106, 40);
+ this.HS4_MAX.Name = "HS4_MAX";
+ this.HS4_MAX.Size = new System.Drawing.Size(43, 20);
+ this.HS4_MAX.TabIndex = 133;
+ this.HS4_MAX.Text = "1500";
+ //
+ // label40
+ //
+ this.label40.AutoSize = true;
+ this.label40.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label40.Location = new System.Drawing.Point(27, 23);
+ this.label40.Name = "label40";
+ this.label40.Size = new System.Drawing.Size(24, 13);
+ this.label40.TabIndex = 134;
+ this.label40.Text = "Min";
+ //
+ // HS3_TRIM
+ //
+ this.HS3_TRIM.Location = new System.Drawing.Point(126, 314);
+ this.HS3_TRIM.Maximum = new decimal(new int[] {
+ 2000,
+ 0,
+ 0,
+ 0});
+ this.HS3_TRIM.Minimum = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ this.HS3_TRIM.Name = "HS3_TRIM";
+ this.HS3_TRIM.Size = new System.Drawing.Size(44, 20);
+ this.HS3_TRIM.TabIndex = 164;
+ this.HS3_TRIM.Value = new decimal(new int[] {
+ 1500,
+ 0,
+ 0,
+ 0});
+ //
+ // HS2_TRIM
+ //
+ this.HS2_TRIM.Location = new System.Drawing.Point(126, 288);
+ this.HS2_TRIM.Maximum = new decimal(new int[] {
+ 2000,
+ 0,
+ 0,
+ 0});
+ this.HS2_TRIM.Minimum = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ this.HS2_TRIM.Name = "HS2_TRIM";
+ this.HS2_TRIM.Size = new System.Drawing.Size(44, 20);
+ this.HS2_TRIM.TabIndex = 163;
+ this.HS2_TRIM.Value = new decimal(new int[] {
+ 1500,
+ 0,
+ 0,
+ 0});
+ //
+ // HS1_TRIM
+ //
+ this.HS1_TRIM.Location = new System.Drawing.Point(126, 262);
+ this.HS1_TRIM.Maximum = new decimal(new int[] {
+ 2000,
+ 0,
+ 0,
+ 0});
+ this.HS1_TRIM.Minimum = new decimal(new int[] {
+ 1000,
+ 0,
+ 0,
+ 0});
+ this.HS1_TRIM.Name = "HS1_TRIM";
+ this.HS1_TRIM.Size = new System.Drawing.Size(44, 20);
+ this.HS1_TRIM.TabIndex = 162;
+ this.HS1_TRIM.Value = new decimal(new int[] {
+ 1500,
+ 0,
+ 0,
+ 0});
+ //
+ // label39
+ //
+ this.label39.AutoSize = true;
+ this.label39.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label39.Location = new System.Drawing.Point(131, 249);
+ this.label39.Name = "label39";
+ this.label39.Size = new System.Drawing.Size(27, 13);
+ this.label39.TabIndex = 161;
+ this.label39.Text = "Trim";
+ //
+ // label38
+ //
+ this.label38.AutoSize = true;
+ this.label38.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label38.Location = new System.Drawing.Point(102, 249);
+ this.label38.Name = "label38";
+ this.label38.Size = new System.Drawing.Size(27, 13);
+ this.label38.TabIndex = 160;
+ this.label38.Text = "Rev";
+ //
+ // label37
+ //
+ this.label37.AutoSize = true;
+ this.label37.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label37.Location = new System.Drawing.Point(54, 249);
+ this.label37.Name = "label37";
+ this.label37.Size = new System.Drawing.Size(44, 13);
+ this.label37.TabIndex = 159;
+ this.label37.Text = "Position";
+ //
+ // label36
+ //
+ this.label36.AutoSize = true;
+ this.label36.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label36.Location = new System.Drawing.Point(17, 249);
+ this.label36.Name = "label36";
+ this.label36.Size = new System.Drawing.Size(35, 13);
+ this.label36.TabIndex = 158;
+ this.label36.Text = "Servo";
+ //
+ // label26
+ //
+ this.label26.AutoSize = true;
+ this.label26.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label26.Location = new System.Drawing.Point(260, 365);
+ this.label26.Name = "label26";
+ this.label26.Size = new System.Drawing.Size(54, 13);
+ this.label26.TabIndex = 157;
+ this.label26.Text = "Pitch Max";
+ //
+ // PIT_MAX
+ //
+ this.PIT_MAX.Location = new System.Drawing.Point(314, 362);
+ this.PIT_MAX.Name = "PIT_MAX";
+ this.PIT_MAX.Size = new System.Drawing.Size(47, 20);
+ this.PIT_MAX.TabIndex = 156;
+ this.PIT_MAX.Text = "4500";
+ //
+ // label25
+ //
+ this.label25.AutoSize = true;
+ this.label25.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label25.Location = new System.Drawing.Point(260, 341);
+ this.label25.Name = "label25";
+ this.label25.Size = new System.Drawing.Size(48, 13);
+ this.label25.TabIndex = 155;
+ this.label25.Text = "Roll Max";
+ //
+ // ROL_MAX
+ //
+ this.ROL_MAX.Location = new System.Drawing.Point(314, 336);
+ this.ROL_MAX.Name = "ROL_MAX";
+ this.ROL_MAX.Size = new System.Drawing.Size(47, 20);
+ this.ROL_MAX.TabIndex = 154;
+ this.ROL_MAX.Text = "4500";
+ //
+ // label23
+ //
+ this.label23.AutoSize = true;
+ this.label23.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label23.Location = new System.Drawing.Point(480, 66);
+ this.label23.Name = "label23";
+ this.label23.Size = new System.Drawing.Size(75, 13);
+ this.label23.TabIndex = 153;
+ this.label23.Text = "Rudder Travel";
+ //
+ // label22
+ //
+ this.label22.AutoSize = true;
+ this.label22.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label22.Location = new System.Drawing.Point(236, 66);
+ this.label22.Name = "label22";
+ this.label22.Size = new System.Drawing.Size(72, 13);
+ this.label22.TabIndex = 150;
+ this.label22.Text = "Swash Travel";
+ //
+ // label20
+ //
+ this.label20.AutoSize = true;
+ this.label20.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label20.Location = new System.Drawing.Point(27, 317);
+ this.label20.Name = "label20";
+ this.label20.Size = new System.Drawing.Size(13, 13);
+ this.label20.TabIndex = 149;
+ this.label20.Text = "3";
+ //
+ // label19
+ //
+ this.label19.AutoSize = true;
+ this.label19.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label19.Location = new System.Drawing.Point(27, 291);
+ this.label19.Name = "label19";
+ this.label19.Size = new System.Drawing.Size(13, 13);
+ this.label19.TabIndex = 148;
+ this.label19.Text = "2";
+ //
+ // label18
+ //
+ this.label18.AutoSize = true;
+ this.label18.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label18.Location = new System.Drawing.Point(27, 265);
+ this.label18.Name = "label18";
+ this.label18.Size = new System.Drawing.Size(13, 13);
+ this.label18.TabIndex = 147;
+ this.label18.Text = "1";
+ //
+ // SV3_POS
+ //
+ this.SV3_POS.Location = new System.Drawing.Point(57, 314);
+ this.SV3_POS.Name = "SV3_POS";
+ this.SV3_POS.Size = new System.Drawing.Size(39, 20);
+ this.SV3_POS.TabIndex = 146;
+ this.SV3_POS.Text = "180";
+ //
+ // SV2_POS
+ //
+ this.SV2_POS.Location = new System.Drawing.Point(57, 288);
+ this.SV2_POS.Name = "SV2_POS";
+ this.SV2_POS.Size = new System.Drawing.Size(39, 20);
+ this.SV2_POS.TabIndex = 145;
+ this.SV2_POS.Text = "60";
+ //
+ // SV1_POS
+ //
+ this.SV1_POS.Location = new System.Drawing.Point(57, 262);
+ this.SV1_POS.Name = "SV1_POS";
+ this.SV1_POS.Size = new System.Drawing.Size(39, 20);
+ this.SV1_POS.TabIndex = 144;
+ this.SV1_POS.Text = "-60";
+ //
+ // HS3_REV
+ //
+ this.HS3_REV.AutoSize = true;
+ this.HS3_REV.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.HS3_REV.Location = new System.Drawing.Point(105, 317);
+ this.HS3_REV.Name = "HS3_REV";
+ this.HS3_REV.Size = new System.Drawing.Size(15, 14);
+ this.HS3_REV.TabIndex = 143;
+ this.HS3_REV.UseVisualStyleBackColor = true;
+ //
+ // HS2_REV
+ //
+ this.HS2_REV.AutoSize = true;
+ this.HS2_REV.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.HS2_REV.Location = new System.Drawing.Point(105, 291);
+ this.HS2_REV.Name = "HS2_REV";
+ this.HS2_REV.Size = new System.Drawing.Size(15, 14);
+ this.HS2_REV.TabIndex = 142;
+ this.HS2_REV.UseVisualStyleBackColor = true;
+ //
+ // HS1_REV
+ //
+ this.HS1_REV.AutoSize = true;
+ this.HS1_REV.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.HS1_REV.Location = new System.Drawing.Point(105, 268);
+ this.HS1_REV.Name = "HS1_REV";
+ this.HS1_REV.Size = new System.Drawing.Size(15, 14);
+ this.HS1_REV.TabIndex = 141;
+ this.HS1_REV.UseVisualStyleBackColor = true;
+ //
+ // label17
+ //
+ this.label17.AutoSize = true;
+ this.label17.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+ this.label17.Location = new System.Drawing.Point(42, 66);
+ this.label17.Name = "label17";
+ this.label17.Size = new System.Drawing.Size(109, 13);
+ this.label17.TabIndex = 140;
+ this.label17.Text = "Swash-Servo position";
+ //
+ // HS4
+ //
+ this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
+ this.HS4.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+ this.HS4.Label = "Rudder";
+ this.HS4.Location = new System.Drawing.Point(396, 93);
+ this.HS4.Maximum = 2200;
+ this.HS4.maxline = 0;
+ this.HS4.Minimum = 800;
+ this.HS4.minline = 0;
+ this.HS4.Name = "HS4";
+ this.HS4.Size = new System.Drawing.Size(242, 42);
+ this.HS4.TabIndex = 152;
+ this.HS4.Value = 1500;
+ this.HS4.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
+ //
+ // HS3
+ //
+ this.HS3.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
+ this.HS3.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+ this.HS3.Label = "Collective";
+ this.HS3.Location = new System.Drawing.Point(239, 95);
+ this.HS3.Maximum = 2200;
+ this.HS3.maxline = 0;
+ this.HS3.Minimum = 800;
+ this.HS3.minline = 0;
+ this.HS3.Name = "HS3";
+ this.HS3.Size = new System.Drawing.Size(42, 213);
+ this.HS3.TabIndex = 151;
+ this.HS3.Value = 1500;
+ this.HS3.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
+ //
+ // Gservoloc
+ //
+ this.Gservoloc.BackColor = System.Drawing.Color.Transparent;
+ this.Gservoloc.BackgroundImage = global::ArdupilotMega.Properties.Resources.Gaugebg;
+ this.Gservoloc.BackgroundImageLayout = System.Windows.Forms.ImageLayout.Zoom;
+ this.Gservoloc.BaseArcColor = System.Drawing.Color.Transparent;
+ this.Gservoloc.BaseArcRadius = 60;
+ this.Gservoloc.BaseArcStart = 90;
+ this.Gservoloc.BaseArcSweep = 360;
+ this.Gservoloc.BaseArcWidth = 2;
+ this.Gservoloc.basesize = new System.Drawing.Size(150, 150);
+ this.Gservoloc.Cap_Idx = ((byte)(0));
+ this.Gservoloc.CapColor = System.Drawing.Color.White;
+ this.Gservoloc.CapColors = new System.Drawing.Color[] {
+ System.Drawing.Color.White,
+ System.Drawing.Color.Black,
+ System.Drawing.Color.Black,
+ System.Drawing.Color.Black,
+ System.Drawing.Color.Black};
+ this.Gservoloc.CapPosition = new System.Drawing.Point(55, 85);
+ this.Gservoloc.CapsPosition = new System.Drawing.Point[] {
+ new System.Drawing.Point(55, 85),
+ new System.Drawing.Point(40, 67),
+ new System.Drawing.Point(10, 10),
+ new System.Drawing.Point(10, 10),
+ new System.Drawing.Point(10, 10)};
+ this.Gservoloc.CapsText = new string[] {
+ "Position",
+ "",
+ "",
+ "",
+ ""};
+ this.Gservoloc.CapText = "Position";
+ this.Gservoloc.Center = new System.Drawing.Point(75, 75);
+ this.Gservoloc.Font = new System.Drawing.Font("Microsoft Sans Serif", 9F);
+ this.Gservoloc.Location = new System.Drawing.Point(20, 93);
+ this.Gservoloc.Margin = new System.Windows.Forms.Padding(0);
+ this.Gservoloc.MaxValue = 180F;
+ this.Gservoloc.MinValue = -180F;
+ this.Gservoloc.Name = "Gservoloc";
+ this.Gservoloc.Need_Idx = ((byte)(3));
+ this.Gservoloc.NeedleColor1 = AGaugeApp.AGauge.NeedleColorEnum.Gray;
+ this.Gservoloc.NeedleColor2 = System.Drawing.Color.White;
+ this.Gservoloc.NeedleEnabled = false;
+ this.Gservoloc.NeedleRadius = 80;
+ this.Gservoloc.NeedlesColor1 = new AGaugeApp.AGauge.NeedleColorEnum[] {
+ AGaugeApp.AGauge.NeedleColorEnum.Gray,
+ AGaugeApp.AGauge.NeedleColorEnum.Red,
+ AGaugeApp.AGauge.NeedleColorEnum.Green,
+ AGaugeApp.AGauge.NeedleColorEnum.Gray};
+ this.Gservoloc.NeedlesColor2 = new System.Drawing.Color[] {
+ System.Drawing.Color.White,
+ System.Drawing.Color.White,
+ System.Drawing.Color.White,
+ System.Drawing.Color.White};
+ this.Gservoloc.NeedlesEnabled = new bool[] {
+ true,
+ true,
+ true,
+ false};
+ this.Gservoloc.NeedlesRadius = new int[] {
+ 60,
+ 60,
+ 60,
+ 80};
+ this.Gservoloc.NeedlesType = new int[] {
+ 0,
+ 0,
+ 0,
+ 0};
+ this.Gservoloc.NeedlesWidth = new int[] {
+ 2,
+ 2,
+ 2,
+ 2};
+ this.Gservoloc.NeedleType = 0;
+ this.Gservoloc.NeedleWidth = 2;
+ this.Gservoloc.Range_Idx = ((byte)(0));
+ this.Gservoloc.RangeColor = System.Drawing.Color.LightGreen;
+ this.Gservoloc.RangeEnabled = false;
+ this.Gservoloc.RangeEndValue = 360F;
+ this.Gservoloc.RangeInnerRadius = 1;
+ this.Gservoloc.RangeOuterRadius = 60;
+ this.Gservoloc.RangesColor = new System.Drawing.Color[] {
+ System.Drawing.Color.LightGreen,
+ System.Drawing.Color.Red,
+ System.Drawing.Color.Orange,
+ System.Drawing.SystemColors.Control,
+ System.Drawing.SystemColors.Control};
+ this.Gservoloc.RangesEnabled = new bool[] {
+ false,
+ false,
+ false,
+ false,
+ false};
+ this.Gservoloc.RangesEndValue = new float[] {
+ 360F,
+ 200F,
+ 150F,
+ 0F,
+ 0F};
+ this.Gservoloc.RangesInnerRadius = new int[] {
+ 1,
+ 1,
+ 1,
+ 70,
+ 70};
+ this.Gservoloc.RangesOuterRadius = new int[] {
+ 60,
+ 60,
+ 60,
+ 80,
+ 80};
+ this.Gservoloc.RangesStartValue = new float[] {
+ 0F,
+ 150F,
+ 75F,
+ 0F,
+ 0F};
+ this.Gservoloc.RangeStartValue = 0F;
+ this.Gservoloc.ScaleLinesInterColor = System.Drawing.Color.White;
+ this.Gservoloc.ScaleLinesInterInnerRadius = 52;
+ this.Gservoloc.ScaleLinesInterOuterRadius = 60;
+ this.Gservoloc.ScaleLinesInterWidth = 1;
+ this.Gservoloc.ScaleLinesMajorColor = System.Drawing.Color.White;
+ this.Gservoloc.ScaleLinesMajorInnerRadius = 50;
+ this.Gservoloc.ScaleLinesMajorOuterRadius = 60;
+ this.Gservoloc.ScaleLinesMajorStepValue = 30F;
+ this.Gservoloc.ScaleLinesMajorWidth = 2;
+ this.Gservoloc.ScaleLinesMinorColor = System.Drawing.Color.White;
+ this.Gservoloc.ScaleLinesMinorInnerRadius = 55;
+ this.Gservoloc.ScaleLinesMinorNumOf = 2;
+ this.Gservoloc.ScaleLinesMinorOuterRadius = 60;
+ this.Gservoloc.ScaleLinesMinorWidth = 1;
+ this.Gservoloc.ScaleNumbersColor = System.Drawing.Color.White;
+ this.Gservoloc.ScaleNumbersFormat = null;
+ this.Gservoloc.ScaleNumbersRadius = 44;
+ this.Gservoloc.ScaleNumbersRotation = 45;
+ this.Gservoloc.ScaleNumbersStartScaleLine = 2;
+ this.Gservoloc.ScaleNumbersStepScaleLines = 1;
+ this.Gservoloc.Size = new System.Drawing.Size(150, 150);
+ this.Gservoloc.TabIndex = 139;
+ this.Gservoloc.Value = 0F;
+ this.Gservoloc.Value0 = -60F;
+ this.Gservoloc.Value1 = 60F;
+ this.Gservoloc.Value2 = 180F;
+ this.Gservoloc.Value3 = 0F;
+ //
+ // ConfigTradHeli
+ //
+ this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+ this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+ this.Controls.Add(this.groupBox5);
+ this.Controls.Add(this.BUT_swash_manual);
+ this.Controls.Add(this.groupBox3);
+ this.Controls.Add(this.BUT_HS4save);
+ this.Controls.Add(this.groupBox1);
+ this.Controls.Add(this.groupBox2);
+ this.Controls.Add(this.HS3_TRIM);
+ this.Controls.Add(this.HS2_TRIM);
+ this.Controls.Add(this.HS1_TRIM);
+ this.Controls.Add(this.label39);
+ this.Controls.Add(this.label38);
+ this.Controls.Add(this.label37);
+ this.Controls.Add(this.label36);
+ this.Controls.Add(this.label26);
+ this.Controls.Add(this.PIT_MAX);
+ this.Controls.Add(this.label25);
+ this.Controls.Add(this.ROL_MAX);
+ this.Controls.Add(this.label23);
+ this.Controls.Add(this.label22);
+ this.Controls.Add(this.label20);
+ this.Controls.Add(this.label19);
+ this.Controls.Add(this.label18);
+ this.Controls.Add(this.SV3_POS);
+ this.Controls.Add(this.SV2_POS);
+ this.Controls.Add(this.SV1_POS);
+ this.Controls.Add(this.HS3_REV);
+ this.Controls.Add(this.HS2_REV);
+ this.Controls.Add(this.HS1_REV);
+ this.Controls.Add(this.label17);
+ this.Controls.Add(this.HS4);
+ this.Controls.Add(this.HS3);
+ this.Controls.Add(this.Gservoloc);
+ this.Name = "ConfigTradHeli";
+ this.Size = new System.Drawing.Size(654, 397);
+ this.groupBox5.ResumeLayout(false);
+ this.groupBox5.PerformLayout();
+ this.groupBox3.ResumeLayout(false);
+ this.groupBox3.PerformLayout();
+ this.groupBox1.ResumeLayout(false);
+ this.groupBox1.PerformLayout();
+ this.groupBox2.ResumeLayout(false);
+ this.groupBox2.PerformLayout();
+ ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).EndInit();
+ ((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).EndInit();
+ this.ResumeLayout(false);
+ this.PerformLayout();
+
+ }
+
+ #endregion
+
+ private System.Windows.Forms.GroupBox groupBox5;
+ private System.Windows.Forms.RadioButton H1_ENABLE;
+ private System.Windows.Forms.RadioButton CCPM;
+ private MyButton BUT_swash_manual;
+ private System.Windows.Forms.Label label41;
+ private System.Windows.Forms.GroupBox groupBox3;
+ private System.Windows.Forms.Label label46;
+ private System.Windows.Forms.Label label45;
+ private System.Windows.Forms.CheckBox GYR_ENABLE;
+ private System.Windows.Forms.TextBox GYR_GAIN;
+ private MyButton BUT_HS4save;
+ private System.Windows.Forms.Label label21;
+ private System.Windows.Forms.TextBox COL_MIN;
+ private System.Windows.Forms.GroupBox groupBox1;
+ private System.Windows.Forms.TextBox COL_MID;
+ private System.Windows.Forms.TextBox COL_MAX;
+ private MyButton BUT_0collective;
+ private System.Windows.Forms.GroupBox groupBox2;
+ private System.Windows.Forms.Label label24;
+ private System.Windows.Forms.TextBox HS4_MIN;
+ private System.Windows.Forms.TextBox HS4_MAX;
+ private System.Windows.Forms.Label label40;
+ private System.Windows.Forms.NumericUpDown HS3_TRIM;
+ private System.Windows.Forms.NumericUpDown HS2_TRIM;
+ private System.Windows.Forms.NumericUpDown HS1_TRIM;
+ private System.Windows.Forms.Label label39;
+ private System.Windows.Forms.Label label38;
+ private System.Windows.Forms.Label label37;
+ private System.Windows.Forms.Label label36;
+ private System.Windows.Forms.Label label26;
+ private System.Windows.Forms.TextBox PIT_MAX;
+ private System.Windows.Forms.Label label25;
+ private System.Windows.Forms.TextBox ROL_MAX;
+ private System.Windows.Forms.Label label23;
+ private System.Windows.Forms.Label label22;
+ private System.Windows.Forms.Label label20;
+ private System.Windows.Forms.Label label19;
+ private System.Windows.Forms.Label label18;
+ private System.Windows.Forms.TextBox SV3_POS;
+ private System.Windows.Forms.TextBox SV2_POS;
+ private System.Windows.Forms.TextBox SV1_POS;
+ private System.Windows.Forms.CheckBox HS3_REV;
+ private System.Windows.Forms.CheckBox HS2_REV;
+ private System.Windows.Forms.CheckBox HS1_REV;
+ private System.Windows.Forms.Label label17;
+ private HorizontalProgressBar2 HS4;
+ private VerticalProgressBar2 HS3;
+ private AGaugeApp.AGauge Gservoloc;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs
new file mode 100644
index 0000000000..7c90f1b31f
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs
@@ -0,0 +1,21 @@
+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.GCSViews.ConfigurationView
+{
+ public partial class ConfigTradHeli : UserControl
+ {
+ public ConfigTradHeli()
+ {
+ InitializeComponent();
+ }
+
+
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx
new file mode 100644
index 0000000000..7080a7d118
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.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/GCSViews/ConfigurationView/Configuration.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.Designer.cs
new file mode 100644
index 0000000000..714e60edae
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.Designer.cs
@@ -0,0 +1,59 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class Configuration
+ {
+ ///
+ /// 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()
+ {
+ System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
+ this.backstageView = new ArdupilotMega.Controls.BackstageView.BackstageView();
+ this.SuspendLayout();
+ //
+ // backstageView
+ //
+ this.backstageView.AutoSize = true;
+ this.backstageView.Dock = System.Windows.Forms.DockStyle.Fill;
+ this.backstageView.Location = new System.Drawing.Point(0, 0);
+ this.backstageView.Name = "backstageView";
+ this.backstageView.Size = new System.Drawing.Size(634, 336);
+ this.backstageView.TabIndex = 0;
+ //
+ // Configuration
+ //
+ this.ClientSize = new System.Drawing.Size(634, 336);
+ this.Controls.Add(this.backstageView);
+ this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
+ this.Name = "Configuration";
+ this.ResumeLayout(false);
+ this.PerformLayout();
+
+ }
+
+ #endregion
+
+ private Controls.BackstageView.BackstageView backstageView;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs
new file mode 100644
index 0000000000..33869ddb02
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs
@@ -0,0 +1,31 @@
+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;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ public partial class Configuration : Form
+ {
+ public Configuration()
+ {
+ InitializeComponent();
+
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigRadioInput(), "Radio Calibration"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigFlightModes(), "Flight Modes"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigHardwareOptions(), "Hardware Options"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigBatteryMonitoring(), "Battery Monitor"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibration(), "Level Calibration"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigArducopter(), "Arducopter Setup"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigArduplane(), "Arduplane Setup"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigArduplane(), "Heli Setup"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigRawParams(), "Raw params (Advanced)"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigPlanner(), "Planner"));
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.resx
new file mode 100644
index 0000000000..222a74addf
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.resx
@@ -0,0 +1,197 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 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
+
+
+
+
+ AAABAAEAICAAAAEAIACoEAAAFgAAACgAAAAgAAAAQAAAAAEAIAAAAAAAABAAABILAAASCwAAAAAAAAAA
+ AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADOxkjAtnoOAKpJ4vyiK
+ c+8nh3D/J4Zv/yeHcP8oi3PvKpJ4vy6fg4AzsZIwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+ AAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADjGo2AyspPfLZ+D/yiQ
+ d/8hlXj/G6F9/xeqg/8XqYL/GKqD/xuhfv8ilnn/KZB3/y2fhP8yspPfN8ajYAAAAAAAAAAAAAAAAAAA
+ AAAAAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADvRrDA1vpzfL6uN/yel
+ hP8XvJD/DMyY/wfQl/8FzJP/A8qS/wPJkf8EypL/BsyU/wnRmP8PzZn/Gb2R/yemhP8tqoz/Mb2a3zbQ
+ qkAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAA4y6ZgMbWV/yin
+ iP8WwZP/Btqf/wDPlf8AyI7/A8aP/yfNnv9T2LP/UNax/03XsP8506b/G8ya/wHKkf8F0Zf/CNuf/xLB
+ kv8fpYT/J7KQ/y7IomAAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAANcajny+w
+ kf8hqoj/CNSd/wDRlf8Axor/Hcyd/3Lhwf+p7Nj/o+vV/57m0/+X5dD/k+TN/4/jzf+K5Mz/fuHH/0PW
+ rf8HzJT/ANCT/wDRlv8OpX//HayI/yrFn58AAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAADDC
+ nmAtro7/H62J/wPWmv8Ay47/AMaO/3XhxP+e6tT/mObP/5Pjy/+Q4sr/jODJ/4ffx/+C3MT/f9vC/3nb
+ wf9y2r7/adq7/2DauP8ZzZv/Fdae/8T/9/9WxKj/HKuI/y7IomAAAAAAAAAAAAAAAAD///8AAAAAAAAA
+ AAAiuZMwKKyM/x6ohf8C1Zr/AMmL/wHGjv+49OL///////////9+3ML/f9zD/4Dcwv9+28L/e9rA/3bZ
+ vv9w1rr/Z9S4/17Rs/9Qz63/Qcyn/3LewP////////////n///8MpH7/JbKP/zXQqUAAAAAAAAAAAP//
+ /wAAAAAAAAAAABymhN8dnn//BNGa/wDKjP8AxY3/sfHf/////////////////2nXt/9w1rv/c9e8/3TX
+ vP9x17z/a9W5/2TTtf9Y0K//SMyp/zXFoP9i07X/////////////////f/LR/wDQlf8epYT/Mb2a3wAA
+ AAAAAAAA////AAAAAAADlnJgFZR1/wq4iv8AzpH/AMCD/4rmzf//////////////////////WdGv/2PU
+ tf9p1rf/atS4/2nUtv9i0rT/Vc+u/0fKpv8zxZz/Ws+w//////////////////////8GyJL/ANCS/xLB
+ kv8tq4z/OMajYAAAAAD///8AAAAAAACHZt8NkW//ANKV/wDChP9i27r//////////////////////9Dx
+ 6P9MzKn/Vc+v/17Rsv9g0rP/XNCx/1XNrv9Fyaf/McSd/1fPr///////////////////////QM2m/ynK
+ oP8JzJX/C9yh/ymmhf80spPfAAAAAP///wAAcUwwAHtc/wCrfP8AyIv/AMKK////////////////////
+ /////////////5Dgyv9Gyqb/TMyq/07Nq/9MzKn/Qcmj/y/Fnf9Wzq3//////////////////////57k
+ 0v8av5T/Lceg/yzOo/8M05v/Hr6T/zCghf80spIw////AABoRYAAclT/AL2H/wDBhf9R1rL/////////
+ ////////4vfw//////////////////H8+P9KzKn/Ocah/zTFnv8qwpj/Us2t////////////////////
+ ////////DLqM/yDBlv8wxp//OM6m/xPPm/8Xz53/LZF5/y+fg4////8AAGNAvwB7Wf8Aw4j/ALyC/4bj
+ yP+g5tL/g93E/2HSsv9Pzqz/Us6s//////////////////////9Yzq//Gr2S/0jLp///////////////
+ /////////////yrDm/8SvI//JMGY/zDHn/81zKT/Is2e/xTUnf8nl3v/LJJ5v////wAAXz3vAIlg/wDA
+ hf8AuoD/quzZ/5Hjyv9628D/ada2/1jRsP9Jy6f/a9a4//////////////////////+Y4s7/////////
+ //////////////////+c4tD/AbaH/xW8kf8jwZj/LcWd/y/Jn/8kzJ3/E9Ca/yGjgf8ri3Tv////AABd
+ PP8Ak2b/AL6D/w/Ekv+m6tf/j+HJ/3vawP9p1rf/W9Gx/0rNqf85yJ//Nsaf////////////////////
+ /////////////////////////////wCwe/8AtoT/ELqP/xu+k/8jwZj/KMeb/yHKm/8QzZf/HqyG/ymI
+ cf////8AAF07/wCSZP8AvYL/GMWU/6Dn1P+K38f/ddi+/27Wuf+E3MX/leHN/6fm1f+l5tX/neLQ////
+ ////////////////////////////////////////j9/J/27Vuv9Tzq7/JsKY/xa/kv8aw5T/FcaW/wvL
+ lf8aqoT/J4dw/////wAAXTv/AJFk/wC9gP8GwY3/mObQ/5rkz/+26dv/y/Hl/8Dt3/+06tz/pebV/5bg
+ zP+g5NL//////////////v///f7+//7+/v//////7fn2////////////tOnb/6Ll0v+v6Nj/jeDI/zXK
+ o/8IxJD/BMqS/xaqgv8lh2//////AABeO+8AgVf/AL1//wDBif/R9uv/1PPq/8Tv5P+36t3/rujY/6Lk
+ 0v+U4cv/jt7J//j8+///////+/38//f8+//2+/r/+Pz7//3+/v/m9/P/9Pv6//D6+P9/28L/jd7J/5jj
+ z/+h5dL/qOvX/4Hmyf8f1J//E596/yOJcO////8AAGA8vwB3U/8p06P/hufM/8Ty5f/D7+T/s+vb/6bm
+ 1P+c4c//j9/K/4vcyP/t+fb///7///j8/P/0+/r/8vr5//P7+f/1+/r/+/39///////i9fL/ZNO1/3HW
+ vP992sH/htzG/4vhyv+S5dD/mO7W/6X74v80noT/Io90v////wAAZkCAAHla/33ny/945cb/nunV/7Xr
+ 3v+l5tT/luDN/4ndxv992cL/1vLq//v9/P/1+/n/8vv4//L69//z+/j/9Pv5/7Xo2//x+vn/////////
+ //+y59n/aNS3/3LWvP932r//fNzD/4Ljyf+J7ND/l/bd/yORdf8knH6A////AABuRzAAdlT/Xc6x/23o
+ xv9s4MH/qurZ/5jiz/+I3cb/edjA/8ju5f/3/Pv/8vv4//H6+P/y+/j/6/f0/7np3v/7/fz//v7+/6fk
+ 1f+56tz///////////9h0bT/aNW4/23Wu/9v3L//dOLG/37w0f9m1rn/Hpt8/ymujTD///8AAAAAAACD
+ X98po4X/Z+7K/1vgvP+A4sf/jOHK/3rZwv+r59f/9Pv6/+/69//v+vf/8vr4/9fy6/9n0rf/VM6t/6Di
+ 0v/N7+f/adO4/1PMrf9t1Lr/i9zI/1/Rs/9h0rX/ZNe4/2bbvf9s5sb/ePfV/z2ylf8lrozfAAAAAP//
+ /wAAAAAAAJNsYAWQbf9U1rP/Vee//0rYsf993sb/pebV//P7+v/s+Pb/6/f1/+749v+s5tj/Vc2u/1jP
+ r/9ZzrD/btW5/1bOr/9Wza//Vs6v/1fOr/9Z0LD/WdCy/1vTtP9d1rX/Xt+8/2btyP9k4L//IaaF/y7D
+ nmAAAAAA////AAAAAAAAAAAAD6J9zyCjgv9S68L/P9+0/2Pevv/5////7/v6/+v59//j9/L/gtvF/1PN
+ r/9Wz7D/Wc+x/1nQsf9Zz7H/WM6w/1fPsP9UzrD/VM+w/1TPrv9U0a//U9Oy/1Tatv9Z5sD/Y/LL/zSx
+ lP8qupbPAAAAAAAAAAD///8AAAAAAAAAAAAYto4wGaeE/y23lP8+5rn/6/////j////w//3/ve/i/2bV
+ uP9Tzq7/Vc+v/1jPsP9Z0LL/WM+w/1fOsf9Wz7D/Us2w/1HOrf9Qzq3/T9Cu/0zSr/9M2LP/TeC5/1bt
+ xP9HxaX/KLKQ/zTPqDAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAkvpdgG6iF/y++m//e/////P///3rl
+ yf9G0K3/VdKy/1bPsf9Wz7H/Vs6w/1bPsP9Sza//Ucyu/0/Nrf9NzKz/S82s/0fOrP9G0a7/QdWv/0Le
+ tP9I6L7/Q8Ok/yitjP8yyKJgAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAmwJlgG6iF/yK3
+ kP8k3q7/H9el/x7Pn/8tzKT/Q9Cs/1HQsP9Q0K7/TM6u/0nMrf9Hzaz/RMyp/0LNqf8+zqn/ONGo/zTV
+ qf833rD/O+S4/zvCof8orIv/MMSfYAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAA
+ AAAkvpdgG6iE/xukgv8gy53/HNql/xzRn/8czJz/HcmZ/yXJnP8qyp7/Lcqg/yzLn/8nypz/JMqc/yTO
+ n/8l1KT/KN2r/y3Tpv8nq4n/JaqJ/yzAm2AAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAA
+ AAAAAAAAAAAAAAAAAAAato8wFKN/zxCScv8RnHn/DbqM/wjIlP8GyZT/BsaS/wbFkf8GxZH/B8WR/wfH
+ k/8IypX/DMmV/xG3jP8WoX3/Fph2/xqkgs8ft5EwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA////AAAA
+ AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJVvYACGZM8Aelr/AHlZ/wCFX/8AiWL/AJlr/wCb
+ bP8AlGf/AI5k/wB/W/8AeFj/AHtb/wCHZd8ClXBgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+ AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAABwSzAAaESAAGI/vwBf
+ Pd8AXTz/AF08/wBdPP8AXz3fAGJAvwBoRIAAcUswAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+ AAAAAAAAAAAAAP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
+ /wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
+ /wD///8A////AP///wD///8A/+AD//+AAP/+AAA//AAAH/gAAA/wAAAH4AAAA+AAAAPAAAABwAAAAYAA
+ AACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAwAAAAcAAAAHgAAAD4AAAA/AA
+ AAf4AAAP/AAAH/4AAD//gAD//+AD//////8=
+
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.Designer.cs
new file mode 100644
index 0000000000..b75d5ddcf3
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.Designer.cs
@@ -0,0 +1,59 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ partial class Setup
+ {
+ ///
+ /// 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()
+ {
+ System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Setup));
+ this.backstageView = new ArdupilotMega.Controls.BackstageView.BackstageView();
+ this.SuspendLayout();
+ //
+ // backstageView
+ //
+ this.backstageView.AutoSize = true;
+ this.backstageView.Dock = System.Windows.Forms.DockStyle.Fill;
+ this.backstageView.Location = new System.Drawing.Point(0, 0);
+ this.backstageView.Name = "backstageView";
+ this.backstageView.Size = new System.Drawing.Size(831, 455);
+ this.backstageView.TabIndex = 0;
+ //
+ // Setup
+ //
+ this.ClientSize = new System.Drawing.Size(831, 455);
+ this.Controls.Add(this.backstageView);
+ this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
+ this.Name = "Setup";
+ this.ResumeLayout(false);
+ this.PerformLayout();
+
+ }
+
+ #endregion
+
+ private Controls.BackstageView.BackstageView backstageView;
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
new file mode 100644
index 0000000000..c87e0f21bf
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
@@ -0,0 +1,27 @@
+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;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+ public partial class Setup : Form
+ {
+ public Setup()
+ {
+ InitializeComponent();
+
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigRadioInput(), "Radio Calibration"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigFlightModes(), "Flight Modes"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigHardwareOptions(), "Hardware Options"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigBatteryMonitoring(), "Battery Monitor"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibration(), "Level Calibration"));
+ this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigTradHeli(), "Heli Setup"));
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.resx
new file mode 100644
index 0000000000..222a74addf
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.resx
@@ -0,0 +1,197 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 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
+
+
+
+
+ AAABAAEAICAAAAEAIACoEAAAFgAAACgAAAAgAAAAQAAAAAEAIAAAAAAAABAAABILAAASCwAAAAAAAAAA
+ AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADOxkjAtnoOAKpJ4vyiK
+ c+8nh3D/J4Zv/yeHcP8oi3PvKpJ4vy6fg4AzsZIwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+ AAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADjGo2AyspPfLZ+D/yiQ
+ d/8hlXj/G6F9/xeqg/8XqYL/GKqD/xuhfv8ilnn/KZB3/y2fhP8yspPfN8ajYAAAAAAAAAAAAAAAAAAA
+ AAAAAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADvRrDA1vpzfL6uN/yel
+ hP8XvJD/DMyY/wfQl/8FzJP/A8qS/wPJkf8EypL/BsyU/wnRmP8PzZn/Gb2R/yemhP8tqoz/Mb2a3zbQ
+ qkAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAA4y6ZgMbWV/yin
+ iP8WwZP/Btqf/wDPlf8AyI7/A8aP/yfNnv9T2LP/UNax/03XsP8506b/G8ya/wHKkf8F0Zf/CNuf/xLB
+ kv8fpYT/J7KQ/y7IomAAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAANcajny+w
+ kf8hqoj/CNSd/wDRlf8Axor/Hcyd/3Lhwf+p7Nj/o+vV/57m0/+X5dD/k+TN/4/jzf+K5Mz/fuHH/0PW
+ rf8HzJT/ANCT/wDRlv8OpX//HayI/yrFn58AAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAADDC
+ nmAtro7/H62J/wPWmv8Ay47/AMaO/3XhxP+e6tT/mObP/5Pjy/+Q4sr/jODJ/4ffx/+C3MT/f9vC/3nb
+ wf9y2r7/adq7/2DauP8ZzZv/Fdae/8T/9/9WxKj/HKuI/y7IomAAAAAAAAAAAAAAAAD///8AAAAAAAAA
+ AAAiuZMwKKyM/x6ohf8C1Zr/AMmL/wHGjv+49OL///////////9+3ML/f9zD/4Dcwv9+28L/e9rA/3bZ
+ vv9w1rr/Z9S4/17Rs/9Qz63/Qcyn/3LewP////////////n///8MpH7/JbKP/zXQqUAAAAAAAAAAAP//
+ /wAAAAAAAAAAABymhN8dnn//BNGa/wDKjP8AxY3/sfHf/////////////////2nXt/9w1rv/c9e8/3TX
+ vP9x17z/a9W5/2TTtf9Y0K//SMyp/zXFoP9i07X/////////////////f/LR/wDQlf8epYT/Mb2a3wAA
+ AAAAAAAA////AAAAAAADlnJgFZR1/wq4iv8AzpH/AMCD/4rmzf//////////////////////WdGv/2PU
+ tf9p1rf/atS4/2nUtv9i0rT/Vc+u/0fKpv8zxZz/Ws+w//////////////////////8GyJL/ANCS/xLB
+ kv8tq4z/OMajYAAAAAD///8AAAAAAACHZt8NkW//ANKV/wDChP9i27r//////////////////////9Dx
+ 6P9MzKn/Vc+v/17Rsv9g0rP/XNCx/1XNrv9Fyaf/McSd/1fPr///////////////////////QM2m/ynK
+ oP8JzJX/C9yh/ymmhf80spPfAAAAAP///wAAcUwwAHtc/wCrfP8AyIv/AMKK////////////////////
+ /////////////5Dgyv9Gyqb/TMyq/07Nq/9MzKn/Qcmj/y/Fnf9Wzq3//////////////////////57k
+ 0v8av5T/Lceg/yzOo/8M05v/Hr6T/zCghf80spIw////AABoRYAAclT/AL2H/wDBhf9R1rL/////////
+ ////////4vfw//////////////////H8+P9KzKn/Ocah/zTFnv8qwpj/Us2t////////////////////
+ ////////DLqM/yDBlv8wxp//OM6m/xPPm/8Xz53/LZF5/y+fg4////8AAGNAvwB7Wf8Aw4j/ALyC/4bj
+ yP+g5tL/g93E/2HSsv9Pzqz/Us6s//////////////////////9Yzq//Gr2S/0jLp///////////////
+ /////////////yrDm/8SvI//JMGY/zDHn/81zKT/Is2e/xTUnf8nl3v/LJJ5v////wAAXz3vAIlg/wDA
+ hf8AuoD/quzZ/5Hjyv9628D/ada2/1jRsP9Jy6f/a9a4//////////////////////+Y4s7/////////
+ //////////////////+c4tD/AbaH/xW8kf8jwZj/LcWd/y/Jn/8kzJ3/E9Ca/yGjgf8ri3Tv////AABd
+ PP8Ak2b/AL6D/w/Ekv+m6tf/j+HJ/3vawP9p1rf/W9Gx/0rNqf85yJ//Nsaf////////////////////
+ /////////////////////////////wCwe/8AtoT/ELqP/xu+k/8jwZj/KMeb/yHKm/8QzZf/HqyG/ymI
+ cf////8AAF07/wCSZP8AvYL/GMWU/6Dn1P+K38f/ddi+/27Wuf+E3MX/leHN/6fm1f+l5tX/neLQ////
+ ////////////////////////////////////////j9/J/27Vuv9Tzq7/JsKY/xa/kv8aw5T/FcaW/wvL
+ lf8aqoT/J4dw/////wAAXTv/AJFk/wC9gP8GwY3/mObQ/5rkz/+26dv/y/Hl/8Dt3/+06tz/pebV/5bg
+ zP+g5NL//////////////v///f7+//7+/v//////7fn2////////////tOnb/6Ll0v+v6Nj/jeDI/zXK
+ o/8IxJD/BMqS/xaqgv8lh2//////AABeO+8AgVf/AL1//wDBif/R9uv/1PPq/8Tv5P+36t3/rujY/6Lk
+ 0v+U4cv/jt7J//j8+///////+/38//f8+//2+/r/+Pz7//3+/v/m9/P/9Pv6//D6+P9/28L/jd7J/5jj
+ z/+h5dL/qOvX/4Hmyf8f1J//E596/yOJcO////8AAGA8vwB3U/8p06P/hufM/8Ty5f/D7+T/s+vb/6bm
+ 1P+c4c//j9/K/4vcyP/t+fb///7///j8/P/0+/r/8vr5//P7+f/1+/r/+/39///////i9fL/ZNO1/3HW
+ vP992sH/htzG/4vhyv+S5dD/mO7W/6X74v80noT/Io90v////wAAZkCAAHla/33ny/945cb/nunV/7Xr
+ 3v+l5tT/luDN/4ndxv992cL/1vLq//v9/P/1+/n/8vv4//L69//z+/j/9Pv5/7Xo2//x+vn/////////
+ //+y59n/aNS3/3LWvP932r//fNzD/4Ljyf+J7ND/l/bd/yORdf8knH6A////AABuRzAAdlT/Xc6x/23o
+ xv9s4MH/qurZ/5jiz/+I3cb/edjA/8ju5f/3/Pv/8vv4//H6+P/y+/j/6/f0/7np3v/7/fz//v7+/6fk
+ 1f+56tz///////////9h0bT/aNW4/23Wu/9v3L//dOLG/37w0f9m1rn/Hpt8/ymujTD///8AAAAAAACD
+ X98po4X/Z+7K/1vgvP+A4sf/jOHK/3rZwv+r59f/9Pv6/+/69//v+vf/8vr4/9fy6/9n0rf/VM6t/6Di
+ 0v/N7+f/adO4/1PMrf9t1Lr/i9zI/1/Rs/9h0rX/ZNe4/2bbvf9s5sb/ePfV/z2ylf8lrozfAAAAAP//
+ /wAAAAAAAJNsYAWQbf9U1rP/Vee//0rYsf993sb/pebV//P7+v/s+Pb/6/f1/+749v+s5tj/Vc2u/1jP
+ r/9ZzrD/btW5/1bOr/9Wza//Vs6v/1fOr/9Z0LD/WdCy/1vTtP9d1rX/Xt+8/2btyP9k4L//IaaF/y7D
+ nmAAAAAA////AAAAAAAAAAAAD6J9zyCjgv9S68L/P9+0/2Pevv/5////7/v6/+v59//j9/L/gtvF/1PN
+ r/9Wz7D/Wc+x/1nQsf9Zz7H/WM6w/1fPsP9UzrD/VM+w/1TPrv9U0a//U9Oy/1Tatv9Z5sD/Y/LL/zSx
+ lP8qupbPAAAAAAAAAAD///8AAAAAAAAAAAAYto4wGaeE/y23lP8+5rn/6/////j////w//3/ve/i/2bV
+ uP9Tzq7/Vc+v/1jPsP9Z0LL/WM+w/1fOsf9Wz7D/Us2w/1HOrf9Qzq3/T9Cu/0zSr/9M2LP/TeC5/1bt
+ xP9HxaX/KLKQ/zTPqDAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAkvpdgG6iF/y++m//e/////P///3rl
+ yf9G0K3/VdKy/1bPsf9Wz7H/Vs6w/1bPsP9Sza//Ucyu/0/Nrf9NzKz/S82s/0fOrP9G0a7/QdWv/0Le
+ tP9I6L7/Q8Ok/yitjP8yyKJgAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAmwJlgG6iF/yK3
+ kP8k3q7/H9el/x7Pn/8tzKT/Q9Cs/1HQsP9Q0K7/TM6u/0nMrf9Hzaz/RMyp/0LNqf8+zqn/ONGo/zTV
+ qf833rD/O+S4/zvCof8orIv/MMSfYAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAA
+ AAAkvpdgG6iE/xukgv8gy53/HNql/xzRn/8czJz/HcmZ/yXJnP8qyp7/Lcqg/yzLn/8nypz/JMqc/yTO
+ n/8l1KT/KN2r/y3Tpv8nq4n/JaqJ/yzAm2AAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAA
+ AAAAAAAAAAAAAAAAAAAato8wFKN/zxCScv8RnHn/DbqM/wjIlP8GyZT/BsaS/wbFkf8GxZH/B8WR/wfH
+ k/8IypX/DMmV/xG3jP8WoX3/Fph2/xqkgs8ft5EwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA////AAAA
+ AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJVvYACGZM8Aelr/AHlZ/wCFX/8AiWL/AJlr/wCb
+ bP8AlGf/AI5k/wB/W/8AeFj/AHtb/wCHZd8ClXBgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+ AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAABwSzAAaESAAGI/vwBf
+ Pd8AXTz/AF08/wBdPP8AXz3fAGJAvwBoRIAAcUswAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+ AAAAAAAAAAAAAP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
+ /wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
+ /wD///8A////AP///wD///8A/+AD//+AAP/+AAA//AAAH/gAAA/wAAAH4AAAA+AAAAPAAAABwAAAAYAA
+ AACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAwAAAAcAAAAHgAAAD4AAAA/AA
+ AAf4AAAP/AAAH/4AAD//gAD//+AD//////8=
+
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
index 651bfd7e74..3f3143eaf2 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
@@ -219,6 +219,7 @@ namespace ArdupilotMega.GCSViews
private void FlightData_Load(object sender, EventArgs e)
{
+ MainV2.bs = bindingSource1;
System.Threading.Thread t11 = new System.Threading.Thread(new System.Threading.ThreadStart(mainloop))
{
@@ -1670,7 +1671,7 @@ namespace ArdupilotMega.GCSViews
return;
}
- MainV2.comPort.setMountConfigure(MAVLink.MAV_MOUNT_MODE.MAV_MOUNT_MODE_GPS_POINT, true, true, true);
+ MainV2.comPort.setMountConfigure(MAVLink.MAV_MOUNT_MODE.GPS_POINT, true, true, true);
MainV2.comPort.setMountControl(gotolocation.Lat, gotolocation.Lng, (int)(intalt / MainV2.cs.multiplierdist), true);
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
index 0310e66b2f..d97921914e 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
@@ -51,7 +51,7 @@ namespace ArdupilotMega.GCSViews
// gps buffer
int gpsbufferindex = 0;
- ArdupilotMega.MAVLink.__mavlink_gps_raw_t[] gpsbuffer = new MAVLink.__mavlink_gps_raw_t[2];
+ ArdupilotMega.MAVLink.mavlink_gps_raw_t[] gpsbuffer = new MAVLink.mavlink_gps_raw_t[5];
// set defaults
int rollgain = 10000;
@@ -704,10 +704,10 @@ namespace ArdupilotMega.GCSViews
float oldax = 0, olday = 0, oldaz = 0;
DateTime oldtime = DateTime.Now;
#if MAVLINK10
- ArdupilotMega.MAVLink.__mavlink_gps_raw_int_t oldgps = new MAVLink.__mavlink_gps_raw_int_t();
+ ArdupilotMega.MAVLink.mavlink_gps_raw_int_t oldgps = new MAVLink.mavlink_gps_raw_int_t();
#endif
- ArdupilotMega.MAVLink.__mavlink_attitude_t oldatt = new ArdupilotMega.MAVLink.__mavlink_attitude_t();
+ ArdupilotMega.MAVLink.mavlink_attitude_t oldatt = new ArdupilotMega.MAVLink.mavlink_attitude_t();
///
/// Recevied UDP packet, process and send required data to serial port.
@@ -718,18 +718,18 @@ namespace ArdupilotMega.GCSViews
private void RECVprocess(byte[] data, int receviedbytes, ArdupilotMega.MAVLink comPort)
{
#if MAVLINK10
- ArdupilotMega.MAVLink.__mavlink_hil_state_t hilstate = new ArdupilotMega.MAVLink.__mavlink_hil_state_t();
+ ArdupilotMega.MAVLink.mavlink_hil_state_t hilstate = new ArdupilotMega.MAVLink.mavlink_hil_state_t();
- ArdupilotMega.MAVLink.__mavlink_gps_raw_int_t gps = new ArdupilotMega.MAVLink.__mavlink_gps_raw_int_t();
+ ArdupilotMega.MAVLink.mavlink_gps_raw_int_t gps = new ArdupilotMega.MAVLink.mavlink_gps_raw_int_t();
#else
- ArdupilotMega.MAVLink.__mavlink_gps_raw_t gps = new ArdupilotMega.MAVLink.__mavlink_gps_raw_t();
+ ArdupilotMega.MAVLink.mavlink_gps_raw_t gps = new ArdupilotMega.MAVLink.mavlink_gps_raw_t();
#endif
- ArdupilotMega.MAVLink.__mavlink_raw_imu_t imu = new ArdupilotMega.MAVLink.__mavlink_raw_imu_t();
+ ArdupilotMega.MAVLink.mavlink_raw_imu_t imu = new ArdupilotMega.MAVLink.mavlink_raw_imu_t();
- ArdupilotMega.MAVLink.__mavlink_attitude_t att = new ArdupilotMega.MAVLink.__mavlink_attitude_t();
+ ArdupilotMega.MAVLink.mavlink_attitude_t att = new ArdupilotMega.MAVLink.mavlink_attitude_t();
- ArdupilotMega.MAVLink.__mavlink_vfr_hud_t asp = new ArdupilotMega.MAVLink.__mavlink_vfr_hud_t();
+ ArdupilotMega.MAVLink.mavlink_vfr_hud_t asp = new ArdupilotMega.MAVLink.mavlink_vfr_hud_t();
if (data[0] == 'D' && data[1] == 'A')
{
@@ -1245,7 +1245,7 @@ namespace ArdupilotMega.GCSViews
#endif
- MAVLink.__mavlink_raw_pressure_t pres = new MAVLink.__mavlink_raw_pressure_t();
+ MAVLink.mavlink_raw_pressure_t pres = new MAVLink.mavlink_raw_pressure_t();
double calc = (101325 * Math.Pow(1 - 2.25577 * Math.Pow(10, -5) * gps.alt, 5.25588)); // updated from valid gps
pres.press_diff1 = (short)(int)(calc - 101325); // 0 alt is 0 pa
@@ -1263,6 +1263,8 @@ namespace ArdupilotMega.GCSViews
// save current fix = 3
gpsbuffer[gpsbufferindex % gpsbuffer.Length] = gps;
+// Console.WriteLine((gpsbufferindex % gpsbuffer.Length) + " " + ((gpsbufferindex + (gpsbuffer.Length - 1)) % gpsbuffer.Length));
+
// return buffer index + 5 = (3 + 5) = 8 % 6 = 2
comPort.sendPacket(gpsbuffer[(gpsbufferindex + (gpsbuffer.Length - 1)) % gpsbuffer.Length]);
diff --git a/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs b/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs
index 16414cbbb5..98d32185e9 100644
--- a/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs
+++ b/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs
@@ -330,14 +330,14 @@ namespace ArdupilotMega.HIL
// send to apm
#if MAVLINK10
- ArdupilotMega.MAVLink.__mavlink_gps_raw_int_t gps = new ArdupilotMega.MAVLink.__mavlink_gps_raw_int_t();
+ ArdupilotMega.MAVLink.mavlink_gps_raw_int_t gps = new ArdupilotMega.MAVLink.mavlink_gps_raw_int_t();
#else
- ArdupilotMega.MAVLink.__mavlink_gps_raw_t gps = new ArdupilotMega.MAVLink.__mavlink_gps_raw_t();
+ ArdupilotMega.MAVLink.mavlink_gps_raw_t gps = new ArdupilotMega.MAVLink.mavlink_gps_raw_t();
#endif
- ArdupilotMega.MAVLink.__mavlink_attitude_t att = new ArdupilotMega.MAVLink.__mavlink_attitude_t();
+ ArdupilotMega.MAVLink.mavlink_attitude_t att = new ArdupilotMega.MAVLink.mavlink_attitude_t();
- ArdupilotMega.MAVLink.__mavlink_vfr_hud_t asp = new ArdupilotMega.MAVLink.__mavlink_vfr_hud_t();
+ ArdupilotMega.MAVLink.mavlink_vfr_hud_t asp = new ArdupilotMega.MAVLink.mavlink_vfr_hud_t();
att.roll = (float)roll * deg2rad;
att.pitch = (float)pitch * deg2rad;
@@ -380,7 +380,7 @@ namespace ArdupilotMega.HIL
MainV2.comPort.sendPacket(att);
- MAVLink.__mavlink_raw_pressure_t pres = new MAVLink.__mavlink_raw_pressure_t();
+ MAVLink.mavlink_raw_pressure_t pres = new MAVLink.mavlink_raw_pressure_t();
double calc = (101325 * Math.Pow(1 - 2.25577 * Math.Pow(10, -5) * gps.alt, 5.25588));
pres.press_diff1 = (short)(int)(calc); // 0 alt is 0 pa
diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
index 9d491c7a68..92e7c613d4 100644
--- a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
+++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
@@ -148,7 +148,7 @@ namespace ArdupilotMega
}
else
{
- MAVLink.__mavlink_rc_channels_override_t rc = new MAVLink.__mavlink_rc_channels_override_t();
+ MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
rc.target_component = MainV2.comPort.compid;
rc.target_system = MainV2.comPort.sysid;
diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs
index 380303e239..b9051e6693 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLink.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs
@@ -269,7 +269,7 @@ namespace ArdupilotMega
if (buffer.Length > 5 && buffer1.Length > 5 && buffer[3] == buffer1[3] && buffer[4] == buffer1[4])
{
- __mavlink_heartbeat_t hb = buffer.ByteArrayToStructure<__mavlink_heartbeat_t>(6);
+ mavlink_heartbeat_t hb = buffer.ByteArrayToStructure(6);
mavlinkversion = hb.mavlink_version;
aptype = hb.type;
@@ -345,7 +345,7 @@ namespace ArdupilotMega
{
bool validPacket = false;
byte a = 0;
- foreach (Type ty in mavstructs)
+ foreach (Type ty in MAVLINK_MESSAGE_INFO)
{
if (ty == indata.GetType())
{
@@ -432,7 +432,7 @@ namespace ArdupilotMega
try
{
- if (logfile != null)
+ if (logfile != null && logfile.BaseStream.CanWrite)
{
lock (logwritelock)
{
@@ -491,7 +491,7 @@ namespace ArdupilotMega
MainV2.giveComport = true;
- __mavlink_param_set_t req = new __mavlink_param_set_t();
+ mavlink_param_set_t req = new mavlink_param_set_t();
req.target_system = sysid;
req.target_component = compid;
@@ -534,7 +534,7 @@ namespace ArdupilotMega
{
if (buffer[5] == MAVLINK_MSG_ID_PARAM_VALUE)
{
- __mavlink_param_value_t par = buffer.ByteArrayToStructure<__mavlink_param_value_t>(6);
+ mavlink_param_value_t par = buffer.ByteArrayToStructure(6);
string st = System.Text.ASCIIEncoding.ASCII.GetString(par.param_id);
@@ -612,7 +612,7 @@ namespace ArdupilotMega
goagain:
- __mavlink_param_request_list_t req = new __mavlink_param_request_list_t();
+ mavlink_param_request_list_t req = new mavlink_param_request_list_t();
req.target_system = sysid;
req.target_component = compid;
@@ -657,7 +657,7 @@ namespace ArdupilotMega
restart = DateTime.Now;
start = DateTime.Now;
- __mavlink_param_value_t par = buffer.ByteArrayToStructure<__mavlink_param_value_t>(6);
+ mavlink_param_value_t par = buffer.ByteArrayToStructure(6);
// set new target
param_total = (par.param_count - 1);
@@ -755,7 +755,7 @@ namespace ArdupilotMega
///
public void stopall(bool forget)
{
- __mavlink_request_data_stream_t req = new __mavlink_request_data_stream_t();
+ mavlink_request_data_stream_t req = new mavlink_request_data_stream_t();
req.target_system = sysid;
req.target_component = compid;
@@ -780,14 +780,14 @@ namespace ArdupilotMega
public void setWPACK()
{
#if MAVLINK10
- MAVLink.__mavlink_mission_ack_t req = new MAVLink.__mavlink_mission_ack_t();
+ 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();
+ MAVLink.mavlink_waypoint_ack_t req = new MAVLink.mavlink_waypoint_ack_t();
req.target_system = sysid;
req.target_component = compid;
req.type = 0;
@@ -802,7 +802,7 @@ namespace ArdupilotMega
MainV2.givecomport = true;
byte[] buffer;
- __mavlink_mission_set_current_t req = new __mavlink_mission_set_current_t();
+ mavlink_mission_set_current_t req = new mavlink_mission_set_current_t();
req.target_system = sysid;
req.target_component = compid;
@@ -847,7 +847,7 @@ namespace ArdupilotMega
MainV2.givecomport = true;
byte[] buffer;
- __mavlink_command_long_t req = new __mavlink_command_long_t();
+ mavlink_command_long_t req = new mavlink_command_long_t();
req.target_system = sysid;
req.target_component = compid;
@@ -899,7 +899,7 @@ namespace ArdupilotMega
{
- var ack = buffer.ByteArrayToStructure<__mavlink_command_ack_t>(6);
+ var ack = buffer.ByteArrayToStructure(6);
if (ack.result == (byte)MAV_RESULT.MAV_RESULT_ACCEPTED)
@@ -919,7 +919,7 @@ namespace ArdupilotMega
MainV2.giveComport = true;
byte[] buffer;
- __mavlink_waypoint_set_current_t req = new __mavlink_waypoint_set_current_t();
+ mavlink_waypoint_set_current_t req = new mavlink_waypoint_set_current_t();
req.target_system = sysid;
req.target_component = compid;
@@ -963,7 +963,7 @@ namespace ArdupilotMega
MainV2.giveComport = true;
byte[] buffer;
- __mavlink_action_t req = new __mavlink_action_t();
+ mavlink_action_t req = new mavlink_action_t();
req.target = sysid;
req.target_component = compid;
@@ -1063,9 +1063,9 @@ namespace ArdupilotMega
}
break;
case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA3:
- if (packetspersecondbuild[MAVLINK_MSG_ID_DCM] < DateTime.Now.AddSeconds(-2))
+ if (packetspersecondbuild[MAVLINK_MSG_ID_AHRS] < DateTime.Now.AddSeconds(-2))
break;
- pps = packetspersecond[MAVLINK_MSG_ID_DCM];
+ pps = packetspersecond[MAVLINK_MSG_ID_AHRS];
if (hzratecheck(pps, hzrate))
{
return;
@@ -1154,7 +1154,7 @@ namespace ArdupilotMega
void getDatastream(byte id, byte hzrate)
{
- __mavlink_request_data_stream_t req = new __mavlink_request_data_stream_t();
+ mavlink_request_data_stream_t req = new mavlink_request_data_stream_t();
req.target_system = sysid;
req.target_component = compid;
@@ -1176,7 +1176,7 @@ namespace ArdupilotMega
MainV2.giveComport = true;
byte[] buffer;
#if MAVLINK10
- __mavlink_mission_request_list_t req = new __mavlink_mission_request_list_t();
+ mavlink_mission_request_list_t req = new mavlink_mission_request_list_t();
req.target_system = sysid;
req.target_component = compid;
@@ -1212,7 +1212,7 @@ namespace ArdupilotMega
- var count = buffer.ByteArrayToStructure<__mavlink_mission_count_t>(6);
+ var count = buffer.ByteArrayToStructure(6);
log.Info("wpcount: " + count.count);
@@ -1227,7 +1227,7 @@ namespace ArdupilotMega
}
#else
- __mavlink_waypoint_request_list_t req = new __mavlink_waypoint_request_list_t();
+ mavlink_waypoint_request_list_t req = new mavlink_waypoint_request_list_t();
req.target_system = sysid;
req.target_component = compid;
@@ -1284,7 +1284,7 @@ namespace ArdupilotMega
MainV2.giveComport = true;
Locationwp loc = new Locationwp();
#if MAVLINK10
- __mavlink_mission_request_t req = new __mavlink_mission_request_t();
+ mavlink_mission_request_t req = new mavlink_mission_request_t();
req.target_system = sysid;
req.target_component = compid;
@@ -1326,12 +1326,12 @@ namespace ArdupilotMega
//Array.Copy(buffer, 6, buffer, 0, buffer.Length - 6);
- var wp = buffer.ByteArrayToStructure<__mavlink_mission_item_t>(6);
+ var wp = buffer.ByteArrayToStructure(6);
#else
- __mavlink_waypoint_request_t req = new __mavlink_waypoint_request_t();
+ mavlink_waypoint_request_t req = new mavlink_waypoint_request_t();
req.target_system = sysid;
req.target_component = compid;
@@ -1369,7 +1369,7 @@ namespace ArdupilotMega
if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT)
{
//Console.WriteLine("getwp ans " + DateTime.Now.Millisecond);
- __mavlink_waypoint_t wp = buffer.ByteArrayToStructure<__mavlink_waypoint_t>(6);
+ mavlink_waypoint_t wp = buffer.ByteArrayToStructure(6);
#endif
@@ -1499,7 +1499,7 @@ namespace ArdupilotMega
textoutput = string.Format("{0:X} {1:X} {2:X} {3:X} {4:X} {5:X} ", header, length, seq, sysid, compid, messid);
- object data = Activator.CreateInstance(mavstructs[messid]);
+ object data = Activator.CreateInstance(MAVLINK_MESSAGE_INFO[messid]);
MavlinkUtil.ByteArrayToStructure(datin, ref data, 6);
@@ -1562,7 +1562,7 @@ namespace ArdupilotMega
{
#if MAVLINK10
MainV2.givecomport = true;
- __mavlink_mission_count_t req = new __mavlink_mission_count_t();
+ mavlink_mission_count_t req = new mavlink_mission_count_t();
req.target_system = sysid;
req.target_component = compid; // MAVLINK_MSG_ID_MISSION_COUNT
@@ -1597,7 +1597,7 @@ namespace ArdupilotMega
- var request = buffer.ByteArrayToStructure<__mavlink_mission_request_t>(6);
+ var request = buffer.ByteArrayToStructure(6);
if (request.seq == 0)
{
@@ -1617,7 +1617,7 @@ namespace ArdupilotMega
}
#else
MainV2.giveComport = true;
- __mavlink_waypoint_count_t req = new __mavlink_waypoint_count_t();
+ mavlink_waypoint_count_t req = new mavlink_waypoint_count_t();
req.target_system = sysid;
req.target_component = compid; // MAVLINK_MSG_ID_WAYPOINT_COUNT
@@ -1649,7 +1649,7 @@ namespace ArdupilotMega
{
if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_REQUEST)
{
- __mavlink_waypoint_request_t request = buffer.ByteArrayToStructure<__mavlink_waypoint_request_t>(6);
+ mavlink_waypoint_request_t request = buffer.ByteArrayToStructure(6);
if (request.seq == 0)
{
@@ -1682,9 +1682,9 @@ namespace ArdupilotMega
{
MainV2.giveComport = true;
#if MAVLINK10
- __mavlink_mission_item_t req = new __mavlink_mission_item_t();
+ mavlink_mission_item_t req = new mavlink_mission_item_t();
#else
- __mavlink_waypoint_t req = new __mavlink_waypoint_t();
+ mavlink_waypoint_t req = new mavlink_waypoint_t();
#endif
req.target_system = sysid;
@@ -1797,7 +1797,7 @@ namespace ArdupilotMega
{
- var ans = buffer.ByteArrayToStructure<__mavlink_mission_ack_t>(6);
+ var ans = buffer.ByteArrayToStructure(6);
log.Info("set wp " + index + " ACK 47 : " + buffer[5] + " ans " + Enum.Parse(typeof(MAV_MISSION_RESULT), ans.type.ToString()));
@@ -1805,7 +1805,7 @@ namespace ArdupilotMega
}
else if (buffer[5] == MAVLINK_MSG_ID_MISSION_REQUEST)
{
- var ans = buffer.ByteArrayToStructure<__mavlink_mission_request_t>(6);
+ var ans = buffer.ByteArrayToStructure(6);
@@ -1828,13 +1828,13 @@ namespace ArdupilotMega
}
#else
if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_ACK)
- { //__mavlink_waypoint_request_t
+ { //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<__mavlink_waypoint_request_t>(6);
+ mavlink_waypoint_request_t ans = buffer.ByteArrayToStructure(6);
if (ans.seq == (index + 1))
{
@@ -1859,7 +1859,7 @@ namespace ArdupilotMega
public void setMountConfigure(MAV_MOUNT_MODE mountmode, bool stabroll, bool stabpitch, bool stabyaw)
{
- __mavlink_mount_configure_t req = new __mavlink_mount_configure_t();
+ mavlink_mount_configure_t req = new mavlink_mount_configure_t();
req.target_system = sysid;
req.target_component = compid;
@@ -1875,7 +1875,7 @@ namespace ArdupilotMega
public void setMountControl(double pa, double pb, double pc, bool islatlng)
{
- __mavlink_mount_control_t req = new __mavlink_mount_control_t();
+ mavlink_mount_control_t req = new mavlink_mount_control_t();
req.target_system = sysid;
req.target_component = compid;
@@ -1902,7 +1902,7 @@ namespace ArdupilotMega
#if MAVLINK10
try
{
- MAVLink.__mavlink_set_mode_t mode = new MAVLink.__mavlink_set_mode_t();
+ MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t();
if (Common.translateMode(modein, ref mode))
{
@@ -1915,9 +1915,9 @@ namespace ArdupilotMega
#else
try
{
- MAVLink.__mavlink_set_nav_mode_t navmode = new MAVLink.__mavlink_set_nav_mode_t();
+ 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();
+ MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t();
if (Common.translateMode(modein, ref navmode, ref mode))
{
@@ -2026,7 +2026,7 @@ namespace ArdupilotMega
if (BaseStream.IsOpen)
{
temp[count] = (byte)BaseStream.ReadByte();
- if (rawlogfile != null)
+ if (rawlogfile != null && rawlogfile.BaseStream.CanWrite)
rawlogfile.Write(temp[count]);
}
}
@@ -2092,7 +2092,7 @@ namespace ArdupilotMega
if (BaseStream.IsOpen)
{
int read = BaseStream.Read(temp, 6, length - 4);
- if (rawlogfile != null)
+ if (rawlogfile != null && rawlogfile.BaseStream.CanWrite)
{
rawlogfile.Write(temp, 0, read);
rawlogfile.BaseStream.Flush();
@@ -2243,7 +2243,7 @@ namespace ArdupilotMega
try
{
- if (logfile != null)
+ if (logfile != null && logfile.BaseStream.CanWrite)
{
lock (logwritelock)
{
@@ -2282,7 +2282,7 @@ namespace ArdupilotMega
if (buffer[5] == MAVLink.MAVLINK_MSG_ID_MISSION_ITEM)
{
- __mavlink_mission_item_t wp = buffer.ByteArrayToStructure<__mavlink_mission_item_t>(6);
+ mavlink_mission_item_t wp = buffer.ByteArrayToStructure(6);
#else
if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_COUNT)
@@ -2293,7 +2293,7 @@ namespace ArdupilotMega
if (buffer[5] == MAVLink.MAVLINK_MSG_ID_WAYPOINT)
{
- __mavlink_waypoint_t wp = buffer.ByteArrayToStructure<__mavlink_waypoint_t>(6);
+ mavlink_waypoint_t wp = buffer.ByteArrayToStructure(6);
#endif
wps[wp.seq] = new PointLatLngAlt(wp.x, wp.y, wp.z, wp.seq.ToString());
@@ -2307,7 +2307,7 @@ namespace ArdupilotMega
MainV2.giveComport = true;
PointLatLngAlt plla = new PointLatLngAlt();
- __mavlink_fence_fetch_point_t req = new __mavlink_fence_fetch_point_t();
+ mavlink_fence_fetch_point_t req = new mavlink_fence_fetch_point_t();
req.idx = (byte)no;
req.target_component = compid;
@@ -2342,7 +2342,7 @@ namespace ArdupilotMega
{
MainV2.giveComport = false;
- __mavlink_fence_point_t fp = buffer.ByteArrayToStructure<__mavlink_fence_point_t>(6);
+ mavlink_fence_point_t fp = buffer.ByteArrayToStructure(6);
plla.Lat = fp.lat;
plla.Lng = fp.lng;
@@ -2358,7 +2358,7 @@ namespace ArdupilotMega
public bool setFencePoint(byte index, PointLatLngAlt plla, byte fencepointcount)
{
- __mavlink_fence_point_t fp = new __mavlink_fence_point_t();
+ mavlink_fence_point_t fp = new mavlink_fence_point_t();
fp.idx = index;
fp.count = fencepointcount;
diff --git a/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs b/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs
index 2f855af568..215c9c545b 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs
@@ -8,1453 +8,1928 @@ namespace ArdupilotMega
#if MAVLINK10
partial class MAVLink
{
+ public const string MAVLINK_BUILD_DATE = "Wed Apr 4 18:13:10 2012";
+ public const string MAVLINK_WIRE_PROTOCOL_VERSION = "1.0";
+ public const int MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 42;
- public const byte MAVLINK_MSG_ID_FENCED_POINT_LEN = 10;
- public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161;
- [StructLayout(LayoutKind.Sequential, Pack = 1)]
- public struct __mavlink_fence_fetch_point_t
+ public const int MAVLINK_LITTLE_ENDIAN = 1;
+ public const int MAVLINK_BIG_ENDIAN = 0;
+
+ public const byte MAVLINK_STX = 254;
+
+ public const byte MAVLINK_ENDIAN = MAVLINK_LITTLE_ENDIAN;
+
+ 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, 0, 0, 26, 0, 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, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 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, 36, 3, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 3};
+
+ 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, 0, 0, 183, 0, 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, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 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, 42, 21, 244, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 247};
+
+ 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 ), null, null, typeof( mavlink_nav_controller_output_t ), null, 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, null, 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 ), 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, 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 ), typeof( mavlink_extended_message_t )};
+
+ public const byte MAVLINK_VERSION = 3;
+
+
+ /** @brief Enumeration of possible mount operation modes */
+ public enum MAV_MOUNT_MODE
{
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte idx; /// point index (first point is 1, 0 is for return point)
+ /// 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,
+
};
-
- public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN = 3;
- public const byte MAVLINK_MSG_ID_FENCE_POINT = 160;
- [StructLayout(LayoutKind.Sequential, Pack = 1)]
- public struct __mavlink_fence_point_t
+
+ /** @brief */
+ public enum MAV_CMD
{
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte idx; /// point index (first point is 1, 0 is for return point)
- public byte count; /// total number of points (for sanity checking)
- public float lat; /// Latitude of point
- public float lng; /// Longitude of point
+ /// 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|
+ NAV_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|
+ NAV_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|
+ NAV_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|
+ NAV_LOITER_TIME=19,
+ /// Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
+ NAV_RETURN_TO_LAUNCH=20,
+ /// Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude|
+ NAV_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|
+ NAV_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|
+ NAV_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|
+ NAV_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|
+ NAV_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,
+ /// |
+ ENUM_END=301,
+
};
-
- 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, 0, 0, 26, 0, 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, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 3};
- 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, 0, 0, 183, 0, 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, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 247};
- public enum MAV_MOUNT_MODE
- {
- MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | */
- MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | */
- MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
- MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
- MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
- MAV_MOUNT_MODE_ENUM_END=5, /* | */
- };
-
- public enum MAV_CMD
- {
- WAYPOINT=16, /* 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| */
- LOITER_UNLIM=17, /* 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_TURNS=18, /* 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_TIME=19, /* 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| */
- RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
- TAKEOFF=22, /* 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| */
- ROI=80, /* 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| */
- PATHPLANNING=81, /* 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| */
- LAST=95, /* 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| */
- CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
- CONDITION_CHANGE_ALT=113, /* 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_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
- CONDITION_YAW=115, /* 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_LAST=159, /* 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| */
- DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */
- DO_JUMP=177, /* 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_CHANGE_SPEED=178, /* 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_SET_HOME=179, /* 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_PARAMETER=180, /* 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_RELAY=181, /* 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_REPEAT_RELAY=182, /* 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_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
- DO_REPEAT_SERVO=184, /* 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_CONTROL_VIDEO=200, /* 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_DIGICAM_CONFIGURE=202, /* 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_CONTROL=203, /* 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_MOUNT_CONFIGURE=204, /* 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_CONTROL=205, /* 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_LAST=240, /* 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| */
- PREFLIGHT_CALIBRATION=241, /* 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_SET_SENSOR_OFFSETS=242, /* 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_STORAGE=245, /* 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_REBOOT_SHUTDOWN=246, /* 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| */
- OVERRIDE_GOTO=252, /* 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| */
- MISSION_START=300, /* 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)| */
- ENUM_END=301, /* | */
- };
-
- public const byte MAVLINK_MSG_ID_AP_ADC = 153;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_ap_adc_t
- {
- public ushort adc1; /// ADC output 1
- public ushort adc2; /// ADC output 2
- public ushort adc3; /// ADC output 3
- public ushort adc4; /// ADC output 4
- public ushort adc5; /// ADC output 5
- public ushort adc6; /// ADC output 6
- };
-
- public const byte MAVLINK_MSG_ID_AP_ADC_LEN = 12;
- public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_digicam_configure_t
- {
- public float extra_value; /// Correspondent value to given extra_param
- public ushort shutter_speed; /// Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte mode; /// Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
- public byte aperture; /// F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
- public byte iso; /// ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
- public byte exposure_type; /// Exposure type enumeration from 1 to N (0 means ignore)
- public byte command_id; /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
- public byte engine_cut_off; /// Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
- public byte extra_param; /// Extra parameters enumeration (0 means ignore)
- };
-
- public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN = 15;
- public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL = 155;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_digicam_control_t
- {
- public float extra_value; /// Correspondent value to given extra_param
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte session; /// 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
- public byte zoom_pos; /// 1 to N //Zoom's absolute position (0 means ignore)
- public byte zoom_step; /// -100 to 100 //Zooming step value to offset zoom from the current position
- public byte focus_lock; /// 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
- public byte shot; /// 0: ignore, 1: shot or start filming
- public byte command_id; /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
- public byte extra_param; /// Extra parameters enumeration (0 means ignore)
- };
-
- public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN = 13;
- public const byte MAVLINK_MSG_ID_MEMINFO = 152;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_meminfo_t
- {
- public ushort brkval; /// heap top
- public ushort freemem; /// free memory
- };
-
- public const byte MAVLINK_MSG_ID_MEMINFO_LEN = 4;
- public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mount_configure_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte mount_mode; /// mount operating mode (see MAV_MOUNT_MODE enum)
- public byte stab_roll; /// (1 = yes, 0 = no)
- public byte stab_pitch; /// (1 = yes, 0 = no)
- public byte stab_yaw; /// (1 = yes, 0 = no)
- };
-
- public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN = 6;
- public const byte MAVLINK_MSG_ID_MOUNT_CONTROL = 157;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mount_control_t
- {
- public int input_a; /// pitch(deg*100) or lat, depending on mount mode
- public int input_b; /// roll(deg*100) or lon depending on mount mode
- public int input_c; /// yaw(deg*100) or alt (in cm) depending on mount mode
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte save_position; /// if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
- };
-
- public const byte MAVLINK_MSG_ID_MOUNT_CONTROL_LEN = 15;
- public const byte MAVLINK_MSG_ID_MOUNT_STATUS = 158;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mount_status_t
- {
- public int pointing_a; /// pitch(deg*100) or lat, depending on mount mode
- public int pointing_b; /// roll(deg*100) or lon depending on mount mode
- public int pointing_c; /// yaw(deg*100) or alt (in cm) depending on mount mode
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_MOUNT_STATUS_LEN = 14;
- public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS = 150;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_sensor_offsets_t
- {
- public float mag_declination; /// magnetic declination (radians)
- public int raw_press; /// raw pressure from barometer
- public int raw_temp; /// raw temperature from barometer
- public float gyro_cal_x; /// gyro X calibration
- public float gyro_cal_y; /// gyro Y calibration
- public float gyro_cal_z; /// gyro Z calibration
- public float accel_cal_x; /// accel X calibration
- public float accel_cal_y; /// accel Y calibration
- public float accel_cal_z; /// accel Z calibration
- public short mag_ofs_x; /// magnetometer X offset
- public short mag_ofs_y; /// magnetometer Y offset
- public short mag_ofs_z; /// magnetometer Z offset
- };
-
- public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN = 42;
- public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_mag_offsets_t
- {
- public short mag_ofs_x; /// magnetometer X offset
- public short mag_ofs_y; /// magnetometer Y offset
- public short mag_ofs_z; /// magnetometer Z offset
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN = 8;
- public enum MAV_AUTOPILOT
- {
- MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */
- MAV_AUTOPILOT_PIXHAWK=1, /* PIXHAWK autopilot, http://pixhawk.ethz.ch | */
- MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */
- MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */
- MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */
- MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */
- MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */
- MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */
- MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */
- MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */
- MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */
- MAV_AUTOPILOT_FP=11, /* FlexiPilot | */
- MAV_AUTOPILOT_ENUM_END=12, /* | */
- };
-
- public enum MAV_MODE_FLAG
- {
- MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */
- MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */
- MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */
- MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */
- MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
- MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */
- MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */
- MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */
- MAV_MODE_FLAG_ENUM_END=129, /* | */
- };
-
- public enum MAV_MODE_FLAG_DECODE_POSITION
- {
- MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */
- MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */
- MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit: 00000100 | */
- MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */
- MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */
- MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */
- MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */
- MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */
- MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */
- };
-
- public enum MAV_GOTO
- {
- MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */
- MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */
- MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */
- MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */
- MAV_GOTO_ENUM_END=4, /* | */
- };
-
- public enum MAV_MODE
- {
- MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */
- MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */
- MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
- MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */
- MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */
- MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */
- MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */
- MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
- MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */
- MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */
- MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */
- MAV_MODE_ENUM_END=221, /* | */
- };
-
- public enum MAV_STATE
- {
- MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */
- MAV_STATE_BOOT=1, /* System is booting up. | */
- MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */
- MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */
- MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */
- MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */
- MAV_STATE_EMERGENCY=6, /* 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. | */
- MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */
- MAV_STATE_ENUM_END=8, /* | */
- };
-
- public enum MAV_TYPE
- {
- MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */
- MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */
- MAV_TYPE_QUADROTOR=2, /* Quadrotor | */
- MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */
- MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */
- MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */
- MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */
- MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */
- MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */
- MAV_TYPE_ROCKET=9, /* Rocket | */
- MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */
- MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */
- MAV_TYPE_SUBMARINE=12, /* Submarine | */
- MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */
- MAV_TYPE_OCTOROTOR=14, /* Octorotor | */
- MAV_TYPE_TRICOPTER=15, /* Octorotor | */
- MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */
- MAV_TYPE_ENUM_END=17, /* | */
- };
-
- 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, /* | */
- MAV_COMPONENT_ENUM_END=251, /* | */
- };
-
- public enum MAV_FRAME
- {
- MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */
- MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */
- MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */
- MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* 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. | */
- MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */
- MAV_FRAME_ENUM_END=5, /* | */
- };
-
- public enum MAV_DATA_STREAM
- {
- MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */
- MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */
- MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */
- MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */
- MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */
- MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */
- MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */
- MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */
- MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */
- MAV_DATA_STREAM_ENUM_END=13, /* | */
- };
-
- public enum MAV_ROI
- {
- MAV_ROI_NONE=0, /* No region of interest. | */
- MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */
- MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */
- MAV_ROI_LOCATION=3, /* Point toward fixed location. | */
- MAV_ROI_TARGET=4, /* Point toward of given id. | */
- MAV_ROI_ENUM_END=5, /* | */
- };
-
- public enum ACK
- {
- ACK_OK=1, /* Command / mission item is ok. | */
- ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */
- ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */
- ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */
- ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */
- ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* 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. | */
- ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */
- ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */
- ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */
- ACK_ENUM_END=10, /* | */
- };
-
- public enum MAV_VAR
- {
- MAV_VAR_FLOAT=0, /* 32 bit float | */
- MAV_VAR_UINT8=1, /* 8 bit unsigned integer | */
- MAV_VAR_INT8=2, /* 8 bit signed integer | */
- MAV_VAR_UINT16=3, /* 16 bit unsigned integer | */
- MAV_VAR_INT16=4, /* 16 bit signed integer | */
- MAV_VAR_UINT32=5, /* 32 bit unsigned integer | */
- MAV_VAR_INT32=6, /* 32 bit signed integer | */
- MAV_VAR_ENUM_END=7, /* | */
- };
-
- public enum MAV_RESULT
- {
- MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */
- MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */
- MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */
- MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */
- MAV_RESULT_FAILED=4, /* Command executed, but failed | */
- MAV_RESULT_ENUM_END=5, /* | */
- };
-
- public enum MAV_MISSION_RESULT
- {
- MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */
- MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */
- MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */
- MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */
- MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */
- MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */
- MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */
- MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */
- MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */
- MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */
- MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */
- MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */
- MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */
- MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */
- MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */
- MAV_MISSION_RESULT_ENUM_END=15, /* | */
- };
-
- public const byte MAVLINK_MSG_ID_ATTITUDE = 30;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_attitude_t
- {
- public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
- public float roll; /// Roll angle (rad)
- public float pitch; /// Pitch angle (rad)
- public float yaw; /// Yaw angle (rad)
- public float rollspeed; /// Roll angular speed (rad/s)
- public float pitchspeed; /// Pitch angular speed (rad/s)
- public float yawspeed; /// Yaw angular speed (rad/s)
- };
-
- public const byte MAVLINK_MSG_ID_ATTITUDE_LEN = 28;
- public const byte MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_attitude_quaternion_t
- {
- public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
- public float q1; /// Quaternion component 1
- public float q2; /// Quaternion component 2
- public float q3; /// Quaternion component 3
- public float q4; /// Quaternion component 4
- public float rollspeed; /// Roll angular speed (rad/s)
- public float pitchspeed; /// Pitch angular speed (rad/s)
- public float yawspeed; /// Yaw angular speed (rad/s)
- };
-
- public const byte MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN = 32;
- public const byte MAVLINK_MSG_ID_AUTH_KEY = 7;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_auth_key_t
- {
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=32)]
- public byte[] key; /// key
- };
-
- public const byte MAVLINK_MSG_ID_AUTH_KEY_LEN = 32;
- public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_change_operator_control_t
- {
- public byte target_system; /// System the GCS requests control for
- public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV
- public byte version; /// 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.
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=25)]
- public byte[] passkey; /// 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 "!?,.-"
- };
-
- public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN = 28;
- public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_change_operator_control_ack_t
- {
- public byte gcs_system_id; /// ID of the GCS this message
- public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV
- public byte ack; /// 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
- };
-
- public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN = 3;
- public const byte MAVLINK_MSG_ID_COMMAND_ACK = 77;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_command_ack_t
- {
- public ushort command; /// Command ID, as defined by MAV_CMD enum.
- public byte result; /// See MAV_RESULT enum
- };
-
- public const byte MAVLINK_MSG_ID_COMMAND_ACK_LEN = 3;
- public const byte MAVLINK_MSG_ID_COMMAND_LONG = 76;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_command_long_t
- {
- public float param1; /// Parameter 1, as defined by MAV_CMD enum.
- public float param2; /// Parameter 2, as defined by MAV_CMD enum.
- public float param3; /// Parameter 3, as defined by MAV_CMD enum.
- public float param4; /// Parameter 4, as defined by MAV_CMD enum.
- public float param5; /// Parameter 5, as defined by MAV_CMD enum.
- public float param6; /// Parameter 6, as defined by MAV_CMD enum.
- public float param7; /// Parameter 7, as defined by MAV_CMD enum.
- public ushort command; /// Command ID, as defined by MAV_CMD enum.
- public byte target_system; /// System which should execute the command
- public byte target_component; /// Component which should execute the command, 0 for all components
- public byte confirmation; /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
- };
-
- public const byte MAVLINK_MSG_ID_COMMAND_LONG_LEN = 33;
- public const byte MAVLINK_MSG_ID_DATA_STREAM = 67;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_data_stream_t
- {
- public ushort message_rate; /// The requested interval between two messages of this type
- public byte stream_id; /// The ID of the requested data stream
- public byte on_off; /// 1 stream is enabled, 0 stream is stopped.
- };
-
- public const byte MAVLINK_MSG_ID_DATA_STREAM_LEN = 4;
- public const byte MAVLINK_MSG_ID_DEBUG = 254;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_debug_t
- {
- public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
- public float value; /// DEBUG value
- public byte ind; /// index of debug variable
- };
-
- public const byte MAVLINK_MSG_ID_DEBUG_LEN = 9;
- public const byte MAVLINK_MSG_ID_DEBUG_VECT = 250;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_debug_vect_t
- {
- public ulong time_usec; /// Timestamp
- public float x; /// x
- public float y; /// y
- public float z; /// z
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=10)]
- public byte[] name; /// Name
- };
-
- public const byte MAVLINK_MSG_ID_DEBUG_VECT_LEN = 30;
- public const byte MAVLINK_MSG_ID_EXTENDED_MESSAGE = 255;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_extended_message_t
- {
- public byte target_system; /// System which should execute the command
- public byte target_component; /// Component which should execute the command, 0 for all components
- public byte protocol_flags; /// Retransmission / ACK flags
- };
-
- public const byte MAVLINK_MSG_ID_EXTENDED_MESSAGE_LEN = 3;
- public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_global_position_int_t
- {
- public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
- public int lat; /// Latitude, expressed as * 1E7
- public int lon; /// Longitude, expressed as * 1E7
- public int alt; /// Altitude in meters, expressed as * 1000 (millimeters), above MSL
- public int relative_alt; /// Altitude above ground in meters, expressed as * 1000 (millimeters)
- public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100
- public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100
- public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100
- public ushort hdg; /// Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
- };
-
- public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN = 28;
- public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT = 52;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_global_position_setpoint_int_t
- {
- public int latitude; /// WGS84 Latitude position in degrees * 1E7
- public int longitude; /// WGS84 Longitude position in degrees * 1E7
- public int altitude; /// WGS84 Altitude in meters * 1000 (positive for up)
- public short yaw; /// Desired yaw angle in degrees * 100
- public byte coordinate_frame; /// Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
- };
-
- public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN = 15;
- public const byte MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_global_vision_position_estimate_t
- {
- public ulong usec; /// Timestamp (milliseconds)
- public float x; /// Global X position
- public float y; /// Global Y position
- public float z; /// Global Z position
- public float roll; /// Roll angle in rad
- public float pitch; /// Pitch angle in rad
- public float yaw; /// Yaw angle in rad
- };
-
- public const byte MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN = 32;
- public const byte MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_gps_global_origin_t
- {
- public int latitude; /// Latitude (WGS84), expressed as * 1E7
- public int longitude; /// Longitude (WGS84), expressed as * 1E7
- public int altitude; /// Altitude(WGS84), expressed as * 1000
- };
-
- public const byte MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN = 12;
- public const byte MAVLINK_MSG_ID_GPS_RAW_INT = 24;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_gps_raw_int_t
- {
- public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public int lat; /// Latitude in 1E7 degrees
- public int lon; /// Longitude in 1E7 degrees
- public int alt; /// Altitude in 1E3 meters (millimeters) above MSL
- public ushort eph; /// GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- public ushort epv; /// GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- public ushort vel; /// GPS ground speed (m/s * 100). If unknown, set to: 65535
- public ushort cog; /// Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
- public byte fix_type; /// 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 satellites_visible; /// Number of satellites visible. If unknown, set to 255
- };
-
- public const byte MAVLINK_MSG_ID_GPS_RAW_INT_LEN = 30;
- public const byte MAVLINK_MSG_ID_GPS_STATUS = 25;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_gps_status_t
- {
- public byte satellites_visible; /// Number of satellites visible
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=20)]
- public byte[] satellite_prn; /// Global satellite ID
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=20)]
- public byte[] satellite_used; /// 0: Satellite not used, 1: used for localization
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=20)]
- public byte[] satellite_elevation; /// Elevation (0: right on top of receiver, 90: on the horizon) of satellite
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=20)]
- public byte[] satellite_azimuth; /// Direction of satellite, 0: 0 deg, 255: 360 deg.
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=20)]
- public byte[] satellite_snr; /// Signal to noise ratio of satellite
- };
-
- public const byte MAVLINK_MSG_ID_GPS_STATUS_LEN = 101;
- public const byte MAVLINK_MSG_ID_HEARTBEAT = 0;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_heartbeat_t
- {
- public uint custom_mode; /// Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
- public byte type; /// Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
- public byte autopilot; /// Autopilot type / class. defined in MAV_CLASS ENUM
- public byte base_mode; /// System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
- public byte system_status; /// System status flag, see MAV_STATUS ENUM
- public byte mavlink_version; /// MAVLink version
- };
-
- public const byte MAVLINK_MSG_ID_HEARTBEAT_LEN = 9;
- public const byte MAVLINK_MSG_ID_HIL_CONTROLS = 91;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_hil_controls_t
- {
- public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public float roll_ailerons; /// Control output -1 .. 1
- public float pitch_elevator; /// Control output -1 .. 1
- public float yaw_rudder; /// Control output -1 .. 1
- public float throttle; /// Throttle 0 .. 1
- public float aux1; /// Aux 1, -1 .. 1
- public float aux2; /// Aux 2, -1 .. 1
- public float aux3; /// Aux 3, -1 .. 1
- public float aux4; /// Aux 4, -1 .. 1
- public byte mode; /// System mode (MAV_MODE)
- public byte nav_mode; /// Navigation mode (MAV_NAV_MODE)
- };
-
- public const byte MAVLINK_MSG_ID_HIL_CONTROLS_LEN = 42;
- public const byte MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_hil_rc_inputs_raw_t
- {
- public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public ushort chan1_raw; /// RC channel 1 value, in microseconds
- public ushort chan2_raw; /// RC channel 2 value, in microseconds
- public ushort chan3_raw; /// RC channel 3 value, in microseconds
- public ushort chan4_raw; /// RC channel 4 value, in microseconds
- public ushort chan5_raw; /// RC channel 5 value, in microseconds
- public ushort chan6_raw; /// RC channel 6 value, in microseconds
- public ushort chan7_raw; /// RC channel 7 value, in microseconds
- public ushort chan8_raw; /// RC channel 8 value, in microseconds
- public ushort chan9_raw; /// RC channel 9 value, in microseconds
- public ushort chan10_raw; /// RC channel 10 value, in microseconds
- public ushort chan11_raw; /// RC channel 11 value, in microseconds
- public ushort chan12_raw; /// RC channel 12 value, in microseconds
- public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100%
- };
-
- public const byte MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN = 33;
- public const byte MAVLINK_MSG_ID_HIL_STATE = 90;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_hil_state_t
- {
- public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public float roll; /// Roll angle (rad)
- public float pitch; /// Pitch angle (rad)
- public float yaw; /// Yaw angle (rad)
- public float rollspeed; /// Roll angular speed (rad/s)
- public float pitchspeed; /// Pitch angular speed (rad/s)
- public float yawspeed; /// Yaw angular speed (rad/s)
- public int lat; /// Latitude, expressed as * 1E7
- public int lon; /// Longitude, expressed as * 1E7
- public int alt; /// Altitude in meters, expressed as * 1000 (millimeters)
- public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100
- public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100
- public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100
- public short xacc; /// X acceleration (mg)
- public short yacc; /// Y acceleration (mg)
- public short zacc; /// Z acceleration (mg)
- };
-
- public const byte MAVLINK_MSG_ID_HIL_STATE_LEN = 56;
- public const byte MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_local_position_ned_t
- {
- public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
- public float x; /// X Position
- public float y; /// Y Position
- public float z; /// Z Position
- public float vx; /// X Speed
- public float vy; /// Y Speed
- public float vz; /// Z Speed
- };
-
- public const byte MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN = 28;
- public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_local_position_setpoint_t
- {
- public float x; /// x position
- public float y; /// y position
- public float z; /// z position
- public float yaw; /// Desired yaw angle
- public byte coordinate_frame; /// Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
- };
-
- public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN = 17;
- public const byte MAVLINK_MSG_ID_MANUAL_CONTROL = 69;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_manual_control_t
- {
- public float roll; /// roll
- public float pitch; /// pitch
- public float yaw; /// yaw
- public float thrust; /// thrust
- public byte target; /// The system to be controlled
- public byte roll_manual; /// roll control enabled auto:0, manual:1
- public byte pitch_manual; /// pitch auto:0, manual:1
- public byte yaw_manual; /// yaw auto:0, manual:1
- public byte thrust_manual; /// thrust auto:0, manual:1
- };
-
- public const byte MAVLINK_MSG_ID_MANUAL_CONTROL_LEN = 21;
- public const byte MAVLINK_MSG_ID_MEMORY_VECT = 249;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_memory_vect_t
- {
- public ushort address; /// Starting address of the debug variables
- public byte ver; /// Version code of the type variable. 0=unknown, type ignored and assumed public short. 1=as below
- public byte type; /// Type code of the memory variables. for ver = 1: 0=16 x public short, 1=16 x public ushort, 2=16 x Q15, 3=16 x 1Q14
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=32)]
- public byte[] value; /// Memory contents at specified address
- };
-
- public const byte MAVLINK_MSG_ID_MEMORY_VECT_LEN = 36;
- public const byte MAVLINK_MSG_ID_MISSION_ACK = 47;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mission_ack_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte type; /// See MAV_MISSION_RESULT enum
- };
-
- public const byte MAVLINK_MSG_ID_MISSION_ACK_LEN = 3;
- public const byte MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mission_clear_all_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN = 2;
- public const byte MAVLINK_MSG_ID_MISSION_COUNT = 44;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mission_count_t
- {
- public ushort count; /// Number of mission items in the sequence
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_MISSION_COUNT_LEN = 4;
- public const byte MAVLINK_MSG_ID_MISSION_CURRENT = 42;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mission_current_t
- {
- public ushort seq; /// Sequence
- };
-
- public const byte MAVLINK_MSG_ID_MISSION_CURRENT_LEN = 2;
- public const byte MAVLINK_MSG_ID_MISSION_ITEM = 39;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mission_item_t
- {
- public float param1; /// PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters
- public float param2; /// PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
- public float param3; /// 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 float param4; /// PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH
- public float x; /// PARAM5 / local: x position, global: latitude
- public float y; /// PARAM6 / y position: global: longitude
- public float z; /// PARAM7 / z position: global: altitude
- public ushort seq; /// Sequence
- public ushort command; /// The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte frame; /// The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
- public byte current; /// false:0, true:1
- public byte autocontinue; /// autocontinue to next wp
- };
-
- public const byte MAVLINK_MSG_ID_MISSION_ITEM_LEN = 37;
- public const byte MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mission_item_reached_t
- {
- public ushort seq; /// Sequence
- };
-
- public const byte MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN = 2;
- public const byte MAVLINK_MSG_ID_MISSION_REQUEST = 40;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mission_request_t
- {
- public ushort seq; /// Sequence
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_MISSION_REQUEST_LEN = 4;
- public const byte MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mission_request_list_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN = 2;
- public const byte MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mission_request_partial_list_t
- {
- public short start_index; /// Start index, 0 by default
- public short end_index; /// End index, -1 by default (-1: send list to end). Else a valid index of the list
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN = 6;
- public const byte MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mission_set_current_t
- {
- public ushort seq; /// Sequence
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN = 4;
- public const byte MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mission_write_partial_list_t
- {
- public short start_index; /// Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
- public short end_index; /// End index, equal or greater than start index.
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN = 6;
- public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_named_value_float_t
- {
- public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
- public float value; /// Floating point value
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=10)]
- public byte[] name; /// Name of the debug variable
- };
-
- public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN = 18;
- public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT = 252;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_named_value_int_t
- {
- public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
- public int value; /// Signed integer value
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=10)]
- public byte[] name; /// Name of the debug variable
- };
-
- public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN = 18;
- public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_nav_controller_output_t
- {
- public float nav_roll; /// Current desired roll in degrees
- public float nav_pitch; /// Current desired pitch in degrees
- public float alt_error; /// Current altitude error in meters
- public float aspd_error; /// Current airspeed error in meters/second
- public float xtrack_error; /// Current crosstrack error on x-y plane in meters
- public short nav_bearing; /// Current desired heading in degrees
- public short target_bearing; /// Bearing to current MISSION/target in degrees
- public ushort wp_dist; /// Distance to active MISSION in meters
- };
-
- public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN = 26;
- public const byte MAVLINK_MSG_ID_OPTICAL_FLOW = 100;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_optical_flow_t
- {
- public ulong time_usec; /// Timestamp (UNIX)
- public float ground_distance; /// Ground distance in meters
- public short flow_x; /// Flow in pixels in x-sensor direction
- public short flow_y; /// Flow in pixels in y-sensor direction
- public byte sensor_id; /// Sensor ID
- public byte quality; /// Optical flow quality / confidence. 0: bad, 255: maximum quality
- };
-
- public const byte MAVLINK_MSG_ID_OPTICAL_FLOW_LEN = 18;
- public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_param_request_list_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN = 2;
- public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_param_request_read_t
- {
- public short param_index; /// Parameter index. Send -1 to use the param ID field as identifier
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=16)]
- public byte[] param_id; /// Onboard parameter id
- };
-
- public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN = 20;
- public const byte MAVLINK_MSG_ID_PARAM_SET = 23;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_param_set_t
- {
- public float param_value; /// Onboard parameter value
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=16)]
- public byte[] param_id; /// Onboard parameter id
- public byte param_type; /// Onboard parameter type: see MAV_VAR enum
- };
-
- public const byte MAVLINK_MSG_ID_PARAM_SET_LEN = 23;
- public const byte MAVLINK_MSG_ID_PARAM_VALUE = 22;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_param_value_t
- {
- public float param_value; /// Onboard parameter value
- public ushort param_count; /// Total number of onboard parameters
- public ushort param_index; /// Index of this onboard parameter
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=16)]
- public byte[] param_id; /// Onboard parameter id
- public byte param_type; /// Onboard parameter type: see MAV_VAR enum
- };
-
- public const byte MAVLINK_MSG_ID_PARAM_VALUE_LEN = 25;
- public const byte MAVLINK_MSG_ID_PING = 4;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_ping_t
- {
- public ulong time_usec; /// Unix timestamp in microseconds
- public uint seq; /// PING sequence
- public byte target_system; /// 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_component; /// 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 const byte MAVLINK_MSG_ID_PING_LEN = 14;
- public const byte MAVLINK_MSG_ID_RAW_IMU = 27;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_raw_imu_t
- {
- public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public short xacc; /// X acceleration (raw)
- public short yacc; /// Y acceleration (raw)
- public short zacc; /// Z acceleration (raw)
- public short xgyro; /// Angular speed around X axis (raw)
- public short ygyro; /// Angular speed around Y axis (raw)
- public short zgyro; /// Angular speed around Z axis (raw)
- public short xmag; /// X Magnetic field (raw)
- public short ymag; /// Y Magnetic field (raw)
- public short zmag; /// Z Magnetic field (raw)
- };
-
- public const byte MAVLINK_MSG_ID_RAW_IMU_LEN = 26;
- public const byte MAVLINK_MSG_ID_RAW_PRESSURE = 28;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_raw_pressure_t
- {
- public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public short press_abs; /// Absolute pressure (raw)
- public short press_diff1; /// Differential pressure 1 (raw)
- public short press_diff2; /// Differential pressure 2 (raw)
- public short temperature; /// Raw Temperature measurement (raw)
- };
-
- public const byte MAVLINK_MSG_ID_RAW_PRESSURE_LEN = 16;
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_rc_channels_override_t
- {
- public ushort chan1_raw; /// RC channel 1 value, in microseconds
- public ushort chan2_raw; /// RC channel 2 value, in microseconds
- public ushort chan3_raw; /// RC channel 3 value, in microseconds
- public ushort chan4_raw; /// RC channel 4 value, in microseconds
- public ushort chan5_raw; /// RC channel 5 value, in microseconds
- public ushort chan6_raw; /// RC channel 6 value, in microseconds
- public ushort chan7_raw; /// RC channel 7 value, in microseconds
- public ushort chan8_raw; /// RC channel 8 value, in microseconds
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN = 18;
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_rc_channels_raw_t
- {
- public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
- public ushort chan1_raw; /// RC channel 1 value, in microseconds
- public ushort chan2_raw; /// RC channel 2 value, in microseconds
- public ushort chan3_raw; /// RC channel 3 value, in microseconds
- public ushort chan4_raw; /// RC channel 4 value, in microseconds
- public ushort chan5_raw; /// RC channel 5 value, in microseconds
- public ushort chan6_raw; /// RC channel 6 value, in microseconds
- public ushort chan7_raw; /// RC channel 7 value, in microseconds
- public ushort chan8_raw; /// RC channel 8 value, in microseconds
- public byte port; /// 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 rssi; /// Receive signal strength indicator, 0: 0%, 255: 100%
- };
-
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN = 22;
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_rc_channels_scaled_t
- {
- public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
- public short chan1_scaled; /// RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan2_scaled; /// RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan3_scaled; /// RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan4_scaled; /// RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan5_scaled; /// RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan6_scaled; /// RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan7_scaled; /// RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan8_scaled; /// RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public byte port; /// 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 rssi; /// Receive signal strength indicator, 0: 0%, 255: 100%
- };
-
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN = 22;
- public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_request_data_stream_t
- {
- public ushort req_message_rate; /// The requested interval between two messages of this type
- public byte target_system; /// The target requested to send the message stream.
- public byte target_component; /// The target requested to send the message stream.
- public byte req_stream_id; /// The ID of the requested data stream
- public byte start_stop; /// 1 to start sending, 0 to stop sending.
- };
-
- public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN = 6;
- public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 59;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t
- {
- public uint time_boot_ms; /// Timestamp in milliseconds since system boot
- public float roll_speed; /// Desired roll angular speed in rad/s
- public float pitch_speed; /// Desired pitch angular speed in rad/s
- public float yaw_speed; /// Desired yaw angular speed in rad/s
- public float thrust; /// Collective thrust, normalized to 0 .. 1
- };
-
- public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN = 20;
- public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 58;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_roll_pitch_yaw_thrust_setpoint_t
- {
- public uint time_boot_ms; /// Timestamp in milliseconds since system boot
- public float roll; /// Desired roll angle in radians
- public float pitch; /// Desired pitch angle in radians
- public float yaw; /// Desired yaw angle in radians
- public float thrust; /// Collective thrust, normalized to 0 .. 1
- };
-
- public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN = 20;
- public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_safety_allowed_area_t
- {
- public float p1x; /// x position 1 / Latitude 1
- public float p1y; /// y position 1 / Longitude 1
- public float p1z; /// z position 1 / Altitude 1
- public float p2x; /// x position 2 / Latitude 2
- public float p2y; /// y position 2 / Longitude 2
- public float p2z; /// z position 2 / Altitude 2
- public byte frame; /// 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 const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN = 25;
- public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_safety_set_allowed_area_t
- {
- public float p1x; /// x position 1 / Latitude 1
- public float p1y; /// y position 1 / Longitude 1
- public float p1z; /// z position 1 / Altitude 1
- public float p2x; /// x position 2 / Latitude 2
- public float p2y; /// y position 2 / Longitude 2
- public float p2z; /// z position 2 / Altitude 2
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte frame; /// 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 const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN = 27;
- public const byte MAVLINK_MSG_ID_SCALED_IMU = 26;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_scaled_imu_t
- {
- public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
- public short xacc; /// X acceleration (mg)
- public short yacc; /// Y acceleration (mg)
- public short zacc; /// Z acceleration (mg)
- public short xgyro; /// Angular speed around X axis (millirad /sec)
- public short ygyro; /// Angular speed around Y axis (millirad /sec)
- public short zgyro; /// Angular speed around Z axis (millirad /sec)
- public short xmag; /// X Magnetic field (milli tesla)
- public short ymag; /// Y Magnetic field (milli tesla)
- public short zmag; /// Z Magnetic field (milli tesla)
- };
-
- public const byte MAVLINK_MSG_ID_SCALED_IMU_LEN = 22;
- public const byte MAVLINK_MSG_ID_SCALED_PRESSURE = 29;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_scaled_pressure_t
- {
- public uint time_boot_ms; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public float press_abs; /// Absolute pressure (hectopascal)
- public float press_diff; /// Differential pressure 1 (hectopascal)
- public short temperature; /// Temperature measurement (0.01 degrees celsius)
- };
-
- public const byte MAVLINK_MSG_ID_SCALED_PRESSURE_LEN = 14;
- public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_servo_output_raw_t
- {
- public uint time_usec; /// Timestamp (since UNIX epoch or microseconds since system boot)
- public ushort servo1_raw; /// Servo output 1 value, in microseconds
- public ushort servo2_raw; /// Servo output 2 value, in microseconds
- public ushort servo3_raw; /// Servo output 3 value, in microseconds
- public ushort servo4_raw; /// Servo output 4 value, in microseconds
- public ushort servo5_raw; /// Servo output 5 value, in microseconds
- public ushort servo6_raw; /// Servo output 6 value, in microseconds
- public ushort servo7_raw; /// Servo output 7 value, in microseconds
- public ushort servo8_raw; /// Servo output 8 value, in microseconds
- public byte port; /// 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 const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN = 21;
- public const byte MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT = 53;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_global_position_setpoint_int_t
- {
- public int latitude; /// WGS84 Latitude position in degrees * 1E7
- public int longitude; /// WGS84 Longitude position in degrees * 1E7
- public int altitude; /// WGS84 Altitude in meters * 1000 (positive for up)
- public short yaw; /// Desired yaw angle in degrees * 100
- public byte coordinate_frame; /// Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
- };
-
- public const byte MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN = 15;
- public const byte MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_gps_global_origin_t
- {
- public int latitude; /// global position * 1E7
- public int longitude; /// global position * 1E7
- public int altitude; /// global position * 1000
- public byte target_system; /// System ID
- };
-
- public const byte MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN = 13;
- public const byte MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT = 50;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_local_position_setpoint_t
- {
- public float x; /// x position
- public float y; /// y position
- public float z; /// z position
- public float yaw; /// Desired yaw angle
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte coordinate_frame; /// Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
- };
-
- public const byte MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN = 19;
- public const byte MAVLINK_MSG_ID_SET_MODE = 11;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_mode_t
- {
- public uint custom_mode; /// The new autopilot-specific mode. This field can be ignored by an autopilot.
- public byte target_system; /// The system setting the mode
- public byte base_mode; /// The new base mode
- };
-
- public const byte MAVLINK_MSG_ID_SET_MODE_LEN = 6;
- public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 57;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_roll_pitch_yaw_speed_thrust_t
- {
- public float roll_speed; /// Desired roll angular speed in rad/s
- public float pitch_speed; /// Desired pitch angular speed in rad/s
- public float yaw_speed; /// Desired yaw angular speed in rad/s
- public float thrust; /// Collective thrust, normalized to 0 .. 1
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN = 18;
- public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 56;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_roll_pitch_yaw_thrust_t
- {
- public float roll; /// Desired roll angle in radians
- public float pitch; /// Desired pitch angle in radians
- public float yaw; /// Desired yaw angle in radians
- public float thrust; /// Collective thrust, normalized to 0 .. 1
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN = 18;
- public const byte MAVLINK_MSG_ID_STATE_CORRECTION = 64;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_state_correction_t
- {
- public float xErr; /// x position error
- public float yErr; /// y position error
- public float zErr; /// z position error
- public float rollErr; /// roll error (radians)
- public float pitchErr; /// pitch error (radians)
- public float yawErr; /// yaw error (radians)
- public float vxErr; /// x velocity
- public float vyErr; /// y velocity
- public float vzErr; /// z velocity
- };
-
- public const byte MAVLINK_MSG_ID_STATE_CORRECTION_LEN = 36;
- public const byte MAVLINK_MSG_ID_STATUSTEXT = 253;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_statustext_t
- {
- public byte severity; /// Severity of status, 0 = info message, 255 = critical fault
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=50)]
- public byte[] text; /// Status text message, without null termination character
- };
-
- public const byte MAVLINK_MSG_ID_STATUSTEXT_LEN = 51;
- public const byte MAVLINK_MSG_ID_SYSTEM_TIME = 2;
- public const byte MAVLINK_MSG_ID_SYS_STATUS = 1;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_sys_status_t
- {
- public uint onboard_control_sensors_present; /// 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 uint onboard_control_sensors_enabled; /// 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 uint onboard_control_sensors_health; /// 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 ushort load; /// Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
- public ushort voltage_battery; /// Battery voltage, in millivolts (1 = 1 millivolt)
- public short current_battery; /// Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
- public ushort drop_rate_comm; /// 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 ushort errors_comm; /// Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
- public ushort errors_count1; /// Autopilot-specific errors
- public ushort errors_count2; /// Autopilot-specific errors
- public ushort errors_count3; /// Autopilot-specific errors
- public ushort errors_count4; /// Autopilot-specific errors
- public byte battery_remaining; /// Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
- };
-
- public const byte MAVLINK_MSG_ID_SYS_STATUS_LEN = 31;
- public const byte MAVLINK_MSG_ID_VFR_HUD = 74;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_vfr_hud_t
- {
- public float airspeed; /// Current airspeed in m/s
- public float groundspeed; /// Current ground speed in m/s
- public float alt; /// Current altitude (MSL), in meters
- public float climb; /// Current climb rate in meters/second
- public short heading; /// Current heading in degrees, in compass units (0..360, 0=north)
- public ushort throttle; /// Current throttle setting in integer percent, 0 to 100
- };
-
- public const byte MAVLINK_MSG_ID_VFR_HUD_LEN = 20;
- public const byte MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_vicon_position_estimate_t
- {
- public ulong usec; /// Timestamp (milliseconds)
- public float x; /// Global X position
- public float y; /// Global Y position
- public float z; /// Global Z position
- public float roll; /// Roll angle in rad
- public float pitch; /// Pitch angle in rad
- public float yaw; /// Yaw angle in rad
- };
-
- public const byte MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN = 32;
- public const byte MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_vision_position_estimate_t
- {
- public ulong usec; /// Timestamp (milliseconds)
- public float x; /// Global X position
- public float y; /// Global Y position
- public float z; /// Global Z position
- public float roll; /// Roll angle in rad
- public float pitch; /// Pitch angle in rad
- public float yaw; /// Yaw angle in rad
- };
-
- public const byte MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN = 32;
- public const byte MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_vision_speed_estimate_t
- {
- public ulong usec; /// Timestamp (milliseconds)
- public float x; /// Global X speed
- public float y; /// Global Y speed
- public float z; /// Global Z speed
- };
-
- public const byte MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN = 20;
- public enum MAV_ACTION
- {
- MAV_ACTION_HOLD = 0,
- MAV_ACTION_MOTORS_START = 1,
- MAV_ACTION_LAUNCH = 2,
- MAV_ACTION_RETURN = 3,
- MAV_ACTION_EMCY_LAND = 4,
- MAV_ACTION_EMCY_KILL = 5,
- MAV_ACTION_CONFIRM_KILL = 6,
- MAV_ACTION_CONTINUE = 7,
- MAV_ACTION_MOTORS_STOP = 8,
- MAV_ACTION_HALT = 9,
- MAV_ACTION_SHUTDOWN = 10,
- MAV_ACTION_REBOOT = 11,
- MAV_ACTION_SET_MANUAL = 12,
- MAV_ACTION_SET_AUTO = 13,
- MAV_ACTION_STORAGE_READ = 14,
- MAV_ACTION_STORAGE_WRITE = 15,
- MAV_ACTION_CALIBRATE_RC = 16,
- MAV_ACTION_CALIBRATE_GYRO = 17,
- MAV_ACTION_CALIBRATE_MAG = 18,
- MAV_ACTION_CALIBRATE_ACC = 19,
- MAV_ACTION_CALIBRATE_PRESSURE = 20,
- MAV_ACTION_REC_START = 21,
- MAV_ACTION_REC_PAUSE = 22,
- MAV_ACTION_REC_STOP = 23,
- MAV_ACTION_TAKEOFF = 24,
- MAV_ACTION_NAVIGATE = 25,
- MAV_ACTION_LAND = 26,
- MAV_ACTION_LOITER = 27,
- MAV_ACTION_SET_ORIGIN = 28,
- MAV_ACTION_RELAY_ON = 29,
- MAV_ACTION_RELAY_OFF = 30,
- MAV_ACTION_GET_IMAGE = 31,
- MAV_ACTION_VIDEO_START = 32,
- MAV_ACTION_VIDEO_STOP = 33,
- MAV_ACTION_RESET_MAP = 34,
- MAV_ACTION_RESET_PLAN = 35,
- MAV_ACTION_DELAY_BEFORE_COMMAND = 36,
- MAV_ACTION_ASCEND_AT_RATE = 37,
- MAV_ACTION_CHANGE_MODE = 38,
- MAV_ACTION_LOITER_MAX_TURNS = 39,
- MAV_ACTION_LOITER_MAX_TIME = 40,
- MAV_ACTION_START_HILSIM = 41,
- MAV_ACTION_STOP_HILSIM = 42,
- MAV_ACTION_NB /// Number of MAV actions
- };
-
-Type[] mavstructs = new Type[] {typeof( __mavlink_heartbeat_t) ,typeof( __mavlink_sys_status_t) ,null ,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) ,null ,null ,typeof( __mavlink_nav_controller_output_t) ,null ,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 ,null ,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 ,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 ,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) ,typeof( __mavlink_extended_message_t) ,null ,};
-
- }
- #endif
+
+ /** @brief */
+ public enum FENCE_ACTION
+ {
+ /// Disable fenced mode |
+ NONE=0,
+ /// Switched to guided mode to return point (fence point 0) |
+ GUIDED=1,
+ /// |
+ ENUM_END=2,
+
+ };
+
+ /** @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,
+
+ };
+
+
+
+ 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;
+ /// raw temperature from barometer
+ public Int32 raw_temp;
+ /// gyro X calibration
+ public Single gyro_cal_x;
+ /// gyro Y calibration
+ public Single gyro_cal_y;
+ /// gyro Z calibration
+ public Single gyro_cal_z;
+ /// accel X calibration
+ public Single accel_cal_x;
+ /// accel Y calibration
+ public Single accel_cal_y;
+ /// accel Z calibration
+ public Single accel_cal_z;
+ /// magnetometer X offset
+ public Int16 mag_ofs_x;
+ /// magnetometer Y offset
+ public Int16 mag_ofs_y;
+ /// magnetometer Z offset
+ 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;
+ /// magnetometer Y offset
+ public Int16 mag_ofs_y;
+ /// magnetometer Z offset
+ public Int16 mag_ofs_z;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ 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;
+ /// free memory
+ 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;
+ /// ADC output 2
+ public UInt16 adc2;
+ /// ADC output 3
+ public UInt16 adc3;
+ /// ADC output 4
+ public UInt16 adc4;
+ /// ADC output 5
+ public UInt16 adc5;
+ /// ADC output 6
+ 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;
+ /// Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
+ public UInt16 shutter_speed;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
+ public byte mode;
+ /// F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
+ public byte aperture;
+ /// ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
+ public byte iso;
+ /// Exposure type enumeration from 1 to N (0 means ignore)
+ 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;
+ /// Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
+ public byte engine_cut_off;
+ /// Extra parameters enumeration (0 means ignore)
+ 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;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
+ public byte session;
+ /// 1 to N //Zoom's absolute position (0 means ignore)
+ public byte zoom_pos;
+ /// -100 to 100 //Zooming step value to offset zoom from the current position
+ public byte zoom_step;
+ /// 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
+ public byte focus_lock;
+ /// 0: ignore, 1: shot or start filming
+ 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;
+ /// Extra parameters enumeration (0 means ignore)
+ 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;
+ /// Component ID
+ public byte target_component;
+ /// mount operating mode (see MAV_MOUNT_MODE enum)
+ public byte mount_mode;
+ /// (1 = yes, 0 = no)
+ public byte stab_roll;
+ /// (1 = yes, 0 = no)
+ public byte stab_pitch;
+ /// (1 = yes, 0 = no)
+ 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;
+ /// roll(deg*100) or lon depending on mount mode
+ public Int32 input_b;
+ /// yaw(deg*100) or alt (in cm) depending on mount mode
+ public Int32 input_c;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ 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 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;
+ /// yaw(deg*100) or alt (in cm) depending on mount mode
+ public Int32 pointing_c;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ 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;
+ /// Longitude of point
+ public Single lng;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// point index (first point is 1, 0 is for return point)
+ public byte idx;
+ /// total number of points (for sanity checking)
+ 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;
+ /// Component ID
+ public byte target_component;
+ /// point index (first point is 1, 0 is for return point)
+ 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;
+ /// number of fence breaches
+ public UInt16 breach_count;
+ /// 0 if currently inside fence, 1 if outside
+ public byte breach_status;
+ /// last breach type (see FENCE_BREACH_* enum)
+ 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;
+ /// Y gyro drift estimate rad/s
+ public Single omegaIy;
+ /// Z gyro drift estimate rad/s
+ public Single omegaIz;
+ /// average accel_weight
+ public Single accel_weight;
+ /// average renormalisation value
+ public Single renorm_val;
+ /// average error_roll_pitch value
+ public Single error_rp;
+ /// average error_yaw value
+ public Single error_yaw;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SIMSTATE = 164;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
+ public struct mavlink_simstate_t
+ {
+ /// Roll angle (rad)
+ public Single roll;
+ /// Pitch angle (rad)
+ public Single pitch;
+ /// Yaw angle (rad)
+ public Single yaw;
+ /// X acceleration m/s/s
+ public Single xacc;
+ /// Y acceleration m/s/s
+ public Single yacc;
+ /// Z acceleration m/s/s
+ public Single zacc;
+ /// Angular speed around X axis rad/s
+ public Single xgyro;
+ /// Angular speed around Y axis rad/s
+ public Single ygyro;
+ /// Angular speed around Z axis rad/s
+ public Single zgyro;
+
+ };
+
+
+ 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 const byte MAVLINK_MSG_ID_RADIO = 166;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)]
+ public struct mavlink_radio_t
+ {
+ /// receive errors
+ public UInt16 rxerrors;
+ /// serial errors
+ public UInt16 serrors;
+ /// count of error corrected packets
+ public UInt16 fixed;
+ /// local signal strength
+ public byte rssi;
+ /// remote signal strength
+ public byte remrssi;
+ /// how full the tx buffer is as a percentage
+ public byte txbuf;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_HEARTBEAT = 0;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)]
+ public struct mavlink_heartbeat_t
+ {
+ /// Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
+ public UInt32 custom_mode;
+ /// Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+ public byte type;
+ /// Autopilot type / class. defined in MAV_CLASS ENUM
+ public byte autopilot;
+ /// System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
+ public byte base_mode;
+ /// System status flag, see MAV_STATUS ENUM
+ public byte system_status;
+ /// 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;
+ /// 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;
+ /// 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;
+ /// Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ public UInt16 load;
+ /// Battery voltage, in millivolts (1 = 1 millivolt)
+ public UInt16 voltage_battery;
+ /// Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
+ 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;
+ /// Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
+ public UInt16 errors_comm;
+ /// Autopilot-specific errors
+ public UInt16 errors_count1;
+ /// Autopilot-specific errors
+ public UInt16 errors_count2;
+ /// Autopilot-specific errors
+ public UInt16 errors_count3;
+ /// Autopilot-specific errors
+ public UInt16 errors_count4;
+ /// Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
+ 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;
+ /// Timestamp of the component clock since boot time in milliseconds.
+ 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;
+ /// PING sequence
+ 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;
+ /// 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 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;
+ /// 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;
+ /// 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 string 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;
+ /// 0: request control of this MAV, 1: Release control of this MAV
+ 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 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 string 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;
+ /// The system setting the mode
+ public byte target_system;
+ /// The new 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
+ public Int16 param_index;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// Onboard parameter id
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
+ public string 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;
+ /// Component ID
+ 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;
+ /// Total number of onboard parameters
+ public UInt16 param_count;
+ /// Index of this onboard parameter
+ public UInt16 param_index;
+ /// Onboard parameter id
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
+ public string param_id;
+ /// Onboard parameter type: see MAV_VAR enum
+ 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;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// Onboard parameter id
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
+ public string param_id;
+ /// Onboard parameter type: see MAV_VAR enum
+ 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;
+ /// Latitude in 1E7 degrees
+ public Int32 lat;
+ /// Longitude in 1E7 degrees
+ public Int32 lon;
+ /// Altitude in 1E3 meters (millimeters) above MSL
+ public Int32 alt;
+ /// GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
+ public UInt16 eph;
+ /// GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
+ public UInt16 epv;
+ /// GPS ground speed (m/s * 100). If unknown, set to: 65535
+ 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;
+ /// 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;
+ /// Number of satellites visible. If unknown, set to 255
+ 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;
+ /// 0: Satellite not used, 1: used for localization
+ [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;
+ /// Direction of satellite, 0: 0 deg, 255: 360 deg.
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+ public byte[] satellite_azimuth;
+ /// Signal to noise ratio of satellite
+ [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;
+ /// X acceleration (mg)
+ public Int16 xacc;
+ /// Y acceleration (mg)
+ public Int16 yacc;
+ /// Z acceleration (mg)
+ public Int16 zacc;
+ /// Angular speed around X axis (millirad /sec)
+ public Int16 xgyro;
+ /// Angular speed around Y axis (millirad /sec)
+ public Int16 ygyro;
+ /// Angular speed around Z axis (millirad /sec)
+ public Int16 zgyro;
+ /// X Magnetic field (milli tesla)
+ public Int16 xmag;
+ /// Y Magnetic field (milli tesla)
+ public Int16 ymag;
+ /// Z Magnetic field (milli tesla)
+ 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;
+ /// X acceleration (raw)
+ public Int16 xacc;
+ /// Y acceleration (raw)
+ public Int16 yacc;
+ /// Z acceleration (raw)
+ public Int16 zacc;
+ /// Angular speed around X axis (raw)
+ public Int16 xgyro;
+ /// Angular speed around Y axis (raw)
+ public Int16 ygyro;
+ /// Angular speed around Z axis (raw)
+ public Int16 zgyro;
+ /// X Magnetic field (raw)
+ public Int16 xmag;
+ /// Y Magnetic field (raw)
+ public Int16 ymag;
+ /// Z Magnetic field (raw)
+ 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;
+ /// Absolute pressure (raw)
+ public Int16 press_abs;
+ /// Differential pressure 1 (raw)
+ public Int16 press_diff1;
+ /// Differential pressure 2 (raw)
+ public Int16 press_diff2;
+ /// Raw Temperature measurement (raw)
+ 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 (microseconds since UNIX epoch or microseconds since system boot)
+ public UInt32 time_boot_ms;
+ /// Absolute pressure (hectopascal)
+ public Single press_abs;
+ /// Differential pressure 1 (hectopascal)
+ public Single press_diff;
+ /// Temperature measurement (0.01 degrees celsius)
+ 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;
+ /// 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;
+
+ };
+
+
+ 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;
+ /// Quaternion component 2
+ public Single q2;
+ /// Quaternion component 3
+ public Single q3;
+ /// Quaternion component 4
+ public Single q4;
+ /// Roll angular speed (rad/s)
+ public Single rollspeed;
+ /// Pitch angular speed (rad/s)
+ public Single pitchspeed;
+ /// Yaw angular speed (rad/s)
+ 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;
+ /// X Position
+ public Single x;
+ /// Y Position
+ public Single y;
+ /// Z Position
+ public Single z;
+ /// X Speed
+ public Single vx;
+ /// Y Speed
+ public Single vy;
+ /// Z Speed
+ 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;
+ /// Latitude, expressed as * 1E7
+ public Int32 lat;
+ /// Longitude, expressed as * 1E7
+ public Int32 lon;
+ /// Altitude in meters, expressed as * 1000 (millimeters), above MSL
+ public Int32 alt;
+ /// Altitude above ground in meters, expressed as * 1000 (millimeters)
+ public Int32 relative_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;
+ /// Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ 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;
+ /// RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan1_scaled;
+ /// RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan2_scaled;
+ /// RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan3_scaled;
+ /// RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan4_scaled;
+ /// RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan5_scaled;
+ /// RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan6_scaled;
+ /// RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan7_scaled;
+ /// RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ 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;
+ /// Receive signal strength indicator, 0: 0%, 255: 100%
+ 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;
+ /// 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;
+ /// 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;
+ /// Receive signal strength indicator, 0: 0%, 255: 100%
+ 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 (since UNIX epoch or microseconds since system boot)
+ public UInt32 time_usec;
+ /// Servo output 1 value, in microseconds
+ public UInt16 servo1_raw;
+ /// Servo output 2 value, in microseconds
+ public UInt16 servo2_raw;
+ /// Servo output 3 value, in microseconds
+ public UInt16 servo3_raw;
+ /// Servo output 4 value, in microseconds
+ public UInt16 servo4_raw;
+ /// Servo output 5 value, in microseconds
+ public UInt16 servo5_raw;
+ /// Servo output 6 value, in microseconds
+ public UInt16 servo6_raw;
+ /// Servo output 7 value, in microseconds
+ public UInt16 servo7_raw;
+ /// Servo output 8 value, in microseconds
+ 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 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;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ 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;
+ /// End index, equal or greater than start index.
+ public Int16 end_index;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ 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;
+ /// PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
+ 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;
+ /// PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH
+ public Single param4;
+ /// PARAM5 / local: x position, global: latitude
+ public Single x;
+ /// PARAM6 / y position: global: longitude
+ public Single y;
+ /// PARAM7 / z position: global: altitude
+ public Single z;
+ /// Sequence
+ public UInt16 seq;
+ /// The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
+ public UInt16 command;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
+ public byte frame;
+ /// false:0, true:1
+ public byte current;
+ /// autocontinue to next wp
+ 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;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ 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;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ 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_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;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ 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;
+ /// Component ID
+ 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 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;
+ /// global position * 1E7
+ public Int32 longitude;
+ /// global position * 1000
+ public Int32 altitude;
+ /// System ID
+ 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;
+ /// Longitude (WGS84), expressed as * 1E7
+ public Int32 longitude;
+ /// Altitude(WGS84), expressed as * 1000
+ 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;
+ /// y position
+ public Single y;
+ /// z position
+ public Single z;
+ /// Desired yaw angle
+ public Single yaw;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
+ 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;
+ /// y position
+ public Single y;
+ /// z position
+ public Single z;
+ /// Desired yaw angle
+ public Single yaw;
+ /// Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
+ 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;
+ /// WGS84 Longitude position in degrees * 1E7
+ public Int32 longitude;
+ /// WGS84 Altitude in meters * 1000 (positive for up)
+ public Int32 altitude;
+ /// Desired yaw angle in degrees * 100
+ public Int16 yaw;
+ /// Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
+ 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;
+ /// WGS84 Longitude position in degrees * 1E7
+ public Int32 longitude;
+ /// WGS84 Altitude in meters * 1000 (positive for up)
+ public Int32 altitude;
+ /// Desired yaw angle in degrees * 100
+ public Int16 yaw;
+ /// Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
+ 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;
+ /// y position 1 / Longitude 1
+ public Single p1y;
+ /// z position 1 / Altitude 1
+ public Single p1z;
+ /// x position 2 / Latitude 2
+ public Single p2x;
+ /// y position 2 / Longitude 2
+ public Single p2y;
+ /// z position 2 / Altitude 2
+ public Single p2z;
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ 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 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;
+ /// z position 1 / Altitude 1
+ public Single p1z;
+ /// x position 2 / Latitude 2
+ public Single p2x;
+ /// y position 2 / Longitude 2
+ public Single p2y;
+ /// z position 2 / Altitude 2
+ 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 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;
+ /// 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_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_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_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;
+ /// 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_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;
+ /// RC channel 10 value, in microseconds
+ public UInt16 chan10_raw;
+ /// RC channel 11 value, in microseconds
+ public UInt16 chan11_raw;
+ /// RC channel 12 value, in microseconds
+ public UInt16 chan12_raw;
+ /// Receive signal strength indicator, 0: 0%, 255: 100%
+ public byte rssi;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_OPTICAL_FLOW = 100;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+ public struct mavlink_optical_flow_t
+ {
+ /// Timestamp (UNIX)
+ public UInt64 time_usec;
+ /// Ground distance in meters
+ public Single ground_distance;
+ /// Flow in pixels in x-sensor direction
+ public Int16 flow_x;
+ /// Flow in pixels in y-sensor direction
+ public Int16 flow_y;
+ /// Sensor ID
+ public byte sensor_id;
+ /// Optical flow quality / confidence. 0: bad, 255: maximum 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;
+ /// Global X position
+ public Single x;
+ /// Global Y position
+ public Single y;
+ /// Global Z position
+ public Single z;
+ /// Roll angle in rad
+ public Single roll;
+ /// Pitch angle in rad
+ public Single pitch;
+ /// Yaw angle in rad
+ 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;
+ /// Global X position
+ public Single x;
+ /// Global Y position
+ public Single y;
+ /// Global Z position
+ public Single z;
+ /// Roll angle in rad
+ public Single roll;
+ /// Pitch angle in rad
+ public Single pitch;
+ /// Yaw angle in rad
+ 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;
+ /// Global X speed
+ public Single x;
+ /// Global Y speed
+ public Single y;
+ /// Global Z speed
+ 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;
+ /// Global X position
+ public Single x;
+ /// Global Y position
+ public Single y;
+ /// Global Z position
+ public Single z;
+ /// Roll angle in rad
+ public Single roll;
+ /// Pitch angle in rad
+ public Single pitch;
+ /// Yaw angle in rad
+ 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;
+ /// Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
+ 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;
+ /// Memory contents at specified address
+ [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;
+ /// x
+ public Single x;
+ /// y
+ public Single y;
+ /// z
+ public Single z;
+ /// Name
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+ public string 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;
+ /// Floating point value
+ public Single value;
+ /// Name of the debug variable
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+ public string 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;
+ /// Signed integer value
+ public Int32 value;
+ /// Name of the debug variable
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+ public string name;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_STATUSTEXT = 253;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=51)]
+ public struct mavlink_statustext_t
+ {
+ /// Severity of status, 0 = info message, 255 = critical fault
+ public byte severity;
+ /// Status text message, without null termination character
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)]
+ public string 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;
+ /// DEBUG value
+ public Single value;
+ /// index of debug variable
+ public byte ind;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_EXTENDED_MESSAGE = 255;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+ public struct mavlink_extended_message_t
+ {
+ /// System which should execute the command
+ public byte target_system;
+ /// Component which should execute the command, 0 for all components
+ public byte target_component;
+ /// Retransmission / ACK flags
+ public byte protocol_flags;
+
+ };
+
+ }
+#endif
}
-
diff --git a/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs b/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs
index 73d32cf4b8..c869616dcf 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs
@@ -5,1192 +5,1783 @@ using System.Runtime.InteropServices;
namespace ArdupilotMega
{
- #if !MAVLINK10
+#if !MAVLINK10
partial class MAVLink
{
- public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5};
- public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 205, 42, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7};
- public enum MAV_MOUNT_MODE
- {
- MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | */
- MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | */
- MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
- MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
- MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
- MAV_MOUNT_MODE_ENUM_END=5, /* | */
- };
-
- public enum MAV_CMD
- {
- WAYPOINT=16, /* Navigate to waypoint. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the waypoint 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 waypoint (rotary wing)| Latitude| Longitude| Altitude| */
- LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of time |Empty| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- LOITER_TURNS=18, /* Loiter around this waypoint for X turns |Turns| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- LOITER_TIME=19, /* Loiter around this waypoint for X seconds |Seconds (decimal)| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
- TAKEOFF=22, /* 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| */
- ROI=80, /* 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)| Waypoint 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| */
- PATHPLANNING=81, /* 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| */
- LAST=95, /* 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| */
- CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
- CONDITION_CHANGE_ALT=113, /* 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_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
- CONDITION_YAW=115, /* 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_LAST=159, /* 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| */
- DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */
- DO_JUMP=177, /* 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_CHANGE_SPEED=178, /* 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_SET_HOME=179, /* 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_PARAMETER=180, /* 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_RELAY=181, /* 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_REPEAT_RELAY=182, /* 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_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
- DO_REPEAT_SERVO=184, /* 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_CONTROL_VIDEO=200, /* Control onboard camera capturing. |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_SET_ROI=201, /* 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
- devices such as cameras.
- |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
- DO_DIGICAM_CONFIGURE=202, /* 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_CONTROL=203, /* 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_MOUNT_CONFIGURE=204, /* 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_CONTROL=205, /* 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_LAST=240, /* 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| */
- PREFLIGHT_CALIBRATION=241, /* 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_STORAGE=245, /* 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| */
- ENUM_END=246, /* | */
- };
-
- public const byte MAVLINK_MSG_ID_AP_ADC = 153;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_ap_adc_t
- {
- public ushort adc1; /// ADC output 1
- public ushort adc2; /// ADC output 2
- public ushort adc3; /// ADC output 3
- public ushort adc4; /// ADC output 4
- public ushort adc5; /// ADC output 5
- public ushort adc6; /// ADC output 6
- };
-
- public const byte MAVLINK_MSG_ID_AP_ADC_LEN = 12;
- public const byte MAVLINK_MSG_ID_DCM = 163;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_dcm_t
- {
- public float omegaIx; /// X gyro drift estimate rad/s
- public float omegaIy; /// Y gyro drift estimate rad/s
- public float omegaIz; /// Z gyro drift estimate rad/s
- public float accel_weight; /// average accel_weight
- public float renorm_val; /// average renormalisation value
- public float error_rp; /// average error_roll_pitch value
- public float error_yaw; /// average error_yaw value
- };
-
- public const byte MAVLINK_MSG_ID_DCM_LEN = 28;
- public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_digicam_configure_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte mode; /// Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
- public ushort shutter_speed; /// Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
- public byte aperture; /// F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
- public byte iso; /// ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
- public byte exposure_type; /// Exposure type enumeration from 1 to N (0 means ignore)
- public byte command_id; /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
- public byte engine_cut_off; /// Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
- public byte extra_param; /// Extra parameters enumeration (0 means ignore)
- public float extra_value; /// Correspondent value to given extra_param
- };
-
- public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN = 15;
- public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL = 155;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_digicam_control_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte session; /// 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
- public byte zoom_pos; /// 1 to N //Zoom's absolute position (0 means ignore)
- public byte zoom_step; /// -100 to 100 //Zooming step value to offset zoom from the current position
- public byte focus_lock; /// 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
- public byte shot; /// 0: ignore, 1: shot or start filming
- public byte command_id; /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
- public byte extra_param; /// Extra parameters enumeration (0 means ignore)
- public float extra_value; /// Correspondent value to given extra_param
- };
-
- public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN = 13;
- public const byte MAVLINK_MSG_ID_FENCED_FETCH_POINT = 161;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_fenced_fetch_point_t
- {
- public byte idx; /// point index (first point is 1, 0 is for return point)
- };
-
- public const byte MAVLINK_MSG_ID_FENCED_FETCH_POINT_LEN = 1;
- public const byte MAVLINK_MSG_ID_FENCED_POINT = 160;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_fenced_point_t
- {
- public byte idx; /// point index (first point is 1, 0 is for return point)
- public byte count; /// total number of points (for sanity checking)
- public float lat; /// Latitude of point
- public float lng; /// Longitude of point
- };
-
- public const byte MAVLINK_MSG_ID_FENCED_POINT_LEN = 10;
- public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_fence_fetch_point_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte idx; /// point index (first point is 1, 0 is for return point)
- };
-
- public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN = 3;
- public const byte MAVLINK_MSG_ID_FENCE_POINT = 160;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_fence_point_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte idx; /// point index (first point is 1, 0 is for return point)
- public byte count; /// total number of points (for sanity checking)
- public float lat; /// Latitude of point
- public float lng; /// Longitude of point
- };
-
- public const byte MAVLINK_MSG_ID_FENCE_POINT_LEN = 12;
- public const byte MAVLINK_MSG_ID_FENCE_STATUS = 162;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_fence_status_t
- {
- public byte breach_status; /// 0 if currently inside fence, 1 if outside
- public ushort breach_count; /// number of fence breaches
- public byte breach_type; /// last breach type (see FENCE_BREACH_* enum)
- public uint breach_time; /// time of last breach in milliseconds since boot
- };
-
- public const byte MAVLINK_MSG_ID_FENCE_STATUS_LEN = 8;
- public const byte MAVLINK_MSG_ID_HWSTATUS = 165;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_hwstatus_t
- {
- public ushort Vcc; /// board voltage (mV)
- public byte I2Cerr; /// I2C error count
- };
-
- public const byte MAVLINK_MSG_ID_HWSTATUS_LEN = 3;
- public const byte MAVLINK_MSG_ID_MEMINFO = 152;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_meminfo_t
- {
- public ushort brkval; /// heap top
- public ushort freemem; /// free memory
- };
-
- public const byte MAVLINK_MSG_ID_MEMINFO_LEN = 4;
- public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mount_configure_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte mount_mode; /// mount operating mode (see MAV_MOUNT_MODE enum)
- public byte stab_roll; /// (1 = yes, 0 = no)
- public byte stab_pitch; /// (1 = yes, 0 = no)
- public byte stab_yaw; /// (1 = yes, 0 = no)
- };
-
- public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN = 6;
- public const byte MAVLINK_MSG_ID_MOUNT_CONTROL = 157;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mount_control_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public int input_a; /// pitch(deg*100) or lat, depending on mount mode
- public int input_b; /// roll(deg*100) or lon depending on mount mode
- public int input_c; /// yaw(deg*100) or alt (in cm) depending on mount mode
- public byte save_position; /// if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
- };
-
- public const byte MAVLINK_MSG_ID_MOUNT_CONTROL_LEN = 15;
- public const byte MAVLINK_MSG_ID_MOUNT_STATUS = 158;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_mount_status_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public int pointing_a; /// pitch(deg*100) or lat, depending on mount mode
- public int pointing_b; /// roll(deg*100) or lon depending on mount mode
- public int pointing_c; /// yaw(deg*100) or alt (in cm) depending on mount mode
- };
-
- public const byte MAVLINK_MSG_ID_MOUNT_STATUS_LEN = 14;
- public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS = 150;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_sensor_offsets_t
- {
- public short mag_ofs_x; /// magnetometer X offset
- public short mag_ofs_y; /// magnetometer Y offset
- public short mag_ofs_z; /// magnetometer Z offset
- public float mag_declination; /// magnetic declination (radians)
- public int raw_press; /// raw pressure from barometer
- public int raw_temp; /// raw temperature from barometer
- public float gyro_cal_x; /// gyro X calibration
- public float gyro_cal_y; /// gyro Y calibration
- public float gyro_cal_z; /// gyro Z calibration
- public float accel_cal_x; /// accel X calibration
- public float accel_cal_y; /// accel Y calibration
- public float accel_cal_z; /// accel Z calibration
- };
-
- public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN = 42;
- public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_mag_offsets_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public short mag_ofs_x; /// magnetometer X offset
- public short mag_ofs_y; /// magnetometer Y offset
- public short mag_ofs_z; /// magnetometer Z offset
- };
-
- public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN = 8;
- public const byte MAVLINK_MSG_ID_SIMSTATE = 164;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_simstate_t
- {
- public float roll; /// Roll angle (rad)
- public float pitch; /// Pitch angle (rad)
- public float yaw; /// Yaw angle (rad)
- public float xacc; /// X acceleration m/s/s
- public float yacc; /// Y acceleration m/s/s
- public float zacc; /// Z acceleration m/s/s
- public float xgyro; /// Angular speed around X axis rad/s
- public float ygyro; /// Angular speed around Y axis rad/s
- public float zgyro; /// Angular speed around Z axis rad/s
- };
-
- public const byte MAVLINK_MSG_ID_SIMSTATE_LEN = 36;
- public enum MAV_DATA_STREAM
- {
- MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */
- MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */
- MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */
- MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */
- MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */
- MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */
- MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */
- MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */
- MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */
- MAV_DATA_STREAM_ENUM_END=13, /* | */
- };
-
- public enum MAV_ROI
- {
- MAV_ROI_NONE=0, /* No region of interest. | */
- MAV_ROI_WPNEXT=1, /* Point toward next waypoint. | */
- MAV_ROI_WPINDEX=2, /* Point toward given waypoint. | */
- MAV_ROI_LOCATION=3, /* Point toward fixed location. | */
- MAV_ROI_TARGET=4, /* Point toward of given id. | */
- MAV_ROI_ENUM_END=5, /* | */
- };
-
- public const byte MAVLINK_MSG_ID_ACTION = 10;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_action_t
- {
- public byte target; /// The system executing the action
- public byte target_component; /// The component executing the action
- public byte action; /// The action id
- };
-
- public const byte MAVLINK_MSG_ID_ACTION_LEN = 3;
- public const byte MAVLINK_MSG_ID_ACTION_ACK = 9;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_action_ack_t
- {
- public byte action; /// The action id
- public byte result; /// 0: Action DENIED, 1: Action executed
- };
-
- public const byte MAVLINK_MSG_ID_ACTION_ACK_LEN = 2;
- public const byte MAVLINK_MSG_ID_ATTITUDE = 30;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_attitude_t
- {
- public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public float roll; /// Roll angle (rad)
- public float pitch; /// Pitch angle (rad)
- public float yaw; /// Yaw angle (rad)
- public float rollspeed; /// Roll angular speed (rad/s)
- public float pitchspeed; /// Pitch angular speed (rad/s)
- public float yawspeed; /// Yaw angular speed (rad/s)
- };
-
- public const byte MAVLINK_MSG_ID_ATTITUDE_LEN = 32;
- public const byte MAVLINK_MSG_ID_AUTH_KEY = 7;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_auth_key_t
- {
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=32)]
- public byte[] key; /// key
- };
-
- public const byte MAVLINK_MSG_ID_AUTH_KEY_LEN = 32;
- public const byte MAVLINK_MSG_ID_BOOT = 1;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_boot_t
- {
- public uint version; /// The onboard software version
- };
-
- public const byte MAVLINK_MSG_ID_BOOT_LEN = 4;
- public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_change_operator_control_t
- {
- public byte target_system; /// System the GCS requests control for
- public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV
- public byte version; /// 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.
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=25)]
- public byte[] passkey; /// 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 "!?,.-"
- };
-
- public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN = 28;
- public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_change_operator_control_ack_t
- {
- public byte gcs_system_id; /// ID of the GCS this message
- public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV
- public byte ack; /// 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
- };
-
- public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN = 3;
- public const byte MAVLINK_MSG_ID_COMMAND = 75;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_command_t
- {
- public byte target_system; /// System which should execute the command
- public byte target_component; /// Component which should execute the command, 0 for all components
- public byte command; /// Command ID, as defined by MAV_CMD enum.
- public byte confirmation; /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
- public float param1; /// Parameter 1, as defined by MAV_CMD enum.
- public float param2; /// Parameter 2, as defined by MAV_CMD enum.
- public float param3; /// Parameter 3, as defined by MAV_CMD enum.
- public float param4; /// Parameter 4, as defined by MAV_CMD enum.
- };
-
- public const byte MAVLINK_MSG_ID_COMMAND_LEN = 20;
- public const byte MAVLINK_MSG_ID_COMMAND_ACK = 76;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_command_ack_t
- {
- public float command; /// Current airspeed in m/s
- public float result; /// 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
- };
-
- public const byte MAVLINK_MSG_ID_COMMAND_ACK_LEN = 8;
- public const byte MAVLINK_MSG_ID_CONTROL_STATUS = 52;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_control_status_t
- {
- public byte position_fix; /// Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
- public byte vision_fix; /// Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
- public byte gps_fix; /// GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
- public byte ahrs_health; /// Attitude estimation health: 0: poor, 255: excellent
- public byte control_att; /// 0: Attitude control disabled, 1: enabled
- public byte control_pos_xy; /// 0: X, Y position control disabled, 1: enabled
- public byte control_pos_z; /// 0: Z position control disabled, 1: enabled
- public byte control_pos_yaw; /// 0: Yaw angle control disabled, 1: enabled
- };
-
- public const byte MAVLINK_MSG_ID_CONTROL_STATUS_LEN = 8;
- public const byte MAVLINK_MSG_ID_DEBUG = 255;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_debug_t
- {
- public byte ind; /// index of debug variable
- public float value; /// DEBUG value
- };
-
- public const byte MAVLINK_MSG_ID_DEBUG_LEN = 5;
- public const byte MAVLINK_MSG_ID_DEBUG_VECT = 251;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_debug_vect_t
- {
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=10)]
- public byte[] name; /// Name
- public ulong usec; /// Timestamp
- public float x; /// x
- public float y; /// y
- public float z; /// z
- };
-
- public const byte MAVLINK_MSG_ID_DEBUG_VECT_LEN = 30;
- public const byte MAVLINK_MSG_ID_GLOBAL_POSITION = 33;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_global_position_t
- {
- public ulong usec; /// Timestamp (microseconds since unix epoch)
- public float lat; /// Latitude, in degrees
- public float lon; /// Longitude, in degrees
- public float alt; /// Absolute altitude, in meters
- public float vx; /// X Speed (in Latitude direction, positive: going north)
- public float vy; /// Y Speed (in Longitude direction, positive: going east)
- public float vz; /// Z Speed (in Altitude direction, positive: going up)
- };
-
- public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_LEN = 32;
- public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 73;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_global_position_int_t
- {
- public int lat; /// Latitude, expressed as * 1E7
- public int lon; /// Longitude, expressed as * 1E7
- public int alt; /// Altitude in meters, expressed as * 1000 (millimeters)
- public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100
- public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100
- public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100
- };
-
- public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN = 18;
- public const byte MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET = 49;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_gps_local_origin_set_t
- {
- public int latitude; /// Latitude (WGS84), expressed as * 1E7
- public int longitude; /// Longitude (WGS84), expressed as * 1E7
- public int altitude; /// Altitude(WGS84), expressed as * 1000
- };
-
- public const byte MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET_LEN = 12;
- public const byte MAVLINK_MSG_ID_GPS_RAW = 32;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_gps_raw_t
- {
- public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public byte fix_type; /// 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 float lat; /// Latitude in degrees
- public float lon; /// Longitude in degrees
- public float alt; /// Altitude in meters
- public float eph; /// GPS HDOP
- public float epv; /// GPS VDOP
- public float v; /// GPS ground speed
- public float hdg; /// Compass heading in degrees, 0..360 degrees
- };
-
- public const byte MAVLINK_MSG_ID_GPS_RAW_LEN = 37;
- public const byte MAVLINK_MSG_ID_GPS_RAW_INT = 25;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_gps_raw_int_t
- {
- public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public byte fix_type; /// 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 int lat; /// Latitude in 1E7 degrees
- public int lon; /// Longitude in 1E7 degrees
- public int alt; /// Altitude in 1E3 meters (millimeters)
- public float eph; /// GPS HDOP
- public float epv; /// GPS VDOP
- public float v; /// GPS ground speed (m/s)
- public float hdg; /// Compass heading in degrees, 0..360 degrees
- };
-
- public const byte MAVLINK_MSG_ID_GPS_RAW_INT_LEN = 37;
- public const byte MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN = 48;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_gps_set_global_origin_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public int latitude; /// global position * 1E7
- public int longitude; /// global position * 1E7
- public int altitude; /// global position * 1000
- };
-
- public const byte MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN_LEN = 14;
- public const byte MAVLINK_MSG_ID_GPS_STATUS = 27;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_gps_status_t
- {
- public byte satellites_visible; /// Number of satellites visible
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=20)]
- public byte[] satellite_prn; /// Global satellite ID
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=20)]
- public byte[] satellite_used; /// 0: Satellite not used, 1: used for localization
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=20)]
- public byte[] satellite_elevation; /// Elevation (0: right on top of receiver, 90: on the horizon) of satellite
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=20)]
- public byte[] satellite_azimuth; /// Direction of satellite, 0: 0 deg, 255: 360 deg.
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=20)]
- public byte[] satellite_snr; /// Signal to noise ratio of satellite
- };
-
- public const byte MAVLINK_MSG_ID_GPS_STATUS_LEN = 101;
- public const byte MAVLINK_MSG_ID_HEARTBEAT = 0;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_heartbeat_t
- {
- public byte type; /// Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
- public byte autopilot; /// Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
- public byte mavlink_version; /// MAVLink version
- };
-
- public const byte MAVLINK_MSG_ID_HEARTBEAT_LEN = 3;
- public const byte MAVLINK_MSG_ID_HIL_CONTROLS = 68;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_hil_controls_t
- {
- public ulong time_us; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public float roll_ailerons; /// Control output -3 .. 1
- public float pitch_elevator; /// Control output -1 .. 1
- public float yaw_rudder; /// Control output -1 .. 1
- public float throttle; /// Throttle 0 .. 1
- public byte mode; /// System mode (MAV_MODE)
- public byte nav_mode; /// Navigation mode (MAV_NAV_MODE)
- };
-
- public const byte MAVLINK_MSG_ID_HIL_CONTROLS_LEN = 26;
- public const byte MAVLINK_MSG_ID_HIL_STATE = 67;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_hil_state_t
- {
- public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public float roll; /// Roll angle (rad)
- public float pitch; /// Pitch angle (rad)
- public float yaw; /// Yaw angle (rad)
- public float rollspeed; /// Roll angular speed (rad/s)
- public float pitchspeed; /// Pitch angular speed (rad/s)
- public float yawspeed; /// Yaw angular speed (rad/s)
- public int lat; /// Latitude, expressed as * 1E7
- public int lon; /// Longitude, expressed as * 1E7
- public int alt; /// Altitude in meters, expressed as * 1000 (millimeters)
- public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100
- public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100
- public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100
- public short xacc; /// X acceleration (mg)
- public short yacc; /// Y acceleration (mg)
- public short zacc; /// Z acceleration (mg)
- };
-
- public const byte MAVLINK_MSG_ID_HIL_STATE_LEN = 56;
- public const byte MAVLINK_MSG_ID_LOCAL_POSITION = 31;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_local_position_t
- {
- public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public float x; /// X Position
- public float y; /// Y Position
- public float z; /// Z Position
- public float vx; /// X Speed
- public float vy; /// Y Speed
- public float vz; /// Z Speed
- };
-
- public const byte MAVLINK_MSG_ID_LOCAL_POSITION_LEN = 32;
- public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_local_position_setpoint_t
- {
- public float x; /// x position
- public float y; /// y position
- public float z; /// z position
- public float yaw; /// Desired yaw angle
- };
-
- public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN = 16;
- public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET = 50;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_local_position_setpoint_set_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public float x; /// x position
- public float y; /// y position
- public float z; /// z position
- public float yaw; /// Desired yaw angle
- };
-
- public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET_LEN = 18;
- public const byte MAVLINK_MSG_ID_MANUAL_CONTROL = 69;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_manual_control_t
- {
- public byte target; /// The system to be controlled
- public float roll; /// roll
- public float pitch; /// pitch
- public float yaw; /// yaw
- public float thrust; /// thrust
- public byte roll_manual; /// roll control enabled auto:0, manual:1
- public byte pitch_manual; /// pitch auto:0, manual:1
- public byte yaw_manual; /// yaw auto:0, manual:1
- public byte thrust_manual; /// thrust auto:0, manual:1
- };
-
- public const byte MAVLINK_MSG_ID_MANUAL_CONTROL_LEN = 21;
- public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 252;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_named_value_float_t
- {
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=10)]
- public byte[] name; /// Name of the debug variable
- public float value; /// Floating point value
- };
-
- public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN = 14;
- public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT = 253;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_named_value_int_t
- {
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=10)]
- public byte[] name; /// Name of the debug variable
- public int value; /// Signed integer value
- };
-
- public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN = 14;
- public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_nav_controller_output_t
- {
- public float nav_roll; /// Current desired roll in degrees
- public float nav_pitch; /// Current desired pitch in degrees
- public short nav_bearing; /// Current desired heading in degrees
- public short target_bearing; /// Bearing to current waypoint/target in degrees
- public ushort wp_dist; /// Distance to active waypoint in meters
- public float alt_error; /// Current altitude error in meters
- public float aspd_error; /// Current airspeed error in meters/second
- public float xtrack_error; /// Current crosstrack error on x-y plane in meters
- };
-
- public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN = 26;
- public const byte MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT = 140;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_object_detection_event_t
- {
- public uint time; /// Timestamp in milliseconds since system boot
- public ushort object_id; /// Object ID
- public byte type; /// Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=20)]
- public byte[] name; /// Name of the object as defined by the detector
- public byte quality; /// Detection quality / confidence. 0: bad, 255: maximum confidence
- public float bearing; /// Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
- public float distance; /// Ground distance in meters
- };
-
- public const byte MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT_LEN = 36;
- public const byte MAVLINK_MSG_ID_OPTICAL_FLOW = 100;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_optical_flow_t
- {
- public ulong time; /// Timestamp (UNIX)
- public byte sensor_id; /// Sensor ID
- public short flow_x; /// Flow in pixels in x-sensor direction
- public short flow_y; /// Flow in pixels in y-sensor direction
- public byte quality; /// Optical flow quality / confidence. 0: bad, 255: maximum quality
- public float ground_distance; /// Ground distance in meters
- };
-
- public const byte MAVLINK_MSG_ID_OPTICAL_FLOW_LEN = 18;
- public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_param_request_list_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN = 2;
- public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_param_request_read_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=15)]
- public byte[] param_id; /// Onboard parameter id
- public short param_index; /// Parameter index. Send -1 to use the param ID field as identifier
- };
-
- public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN = 19;
- public const byte MAVLINK_MSG_ID_PARAM_SET = 23;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_param_set_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=15)]
- public byte[] param_id; /// Onboard parameter id
- public float param_value; /// Onboard parameter value
- };
-
- public const byte MAVLINK_MSG_ID_PARAM_SET_LEN = 21;
- public const byte MAVLINK_MSG_ID_PARAM_VALUE = 22;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_param_value_t
- {
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=15)]
- public byte[] param_id; /// Onboard parameter id
- public float param_value; /// Onboard parameter value
- public ushort param_count; /// Total number of onboard parameters
- public ushort param_index; /// Index of this onboard parameter
- };
-
- public const byte MAVLINK_MSG_ID_PARAM_VALUE_LEN = 23;
- public const byte MAVLINK_MSG_ID_PING = 3;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_ping_t
- {
- public uint seq; /// PING sequence
- public byte target_system; /// 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_component; /// 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 ulong time; /// Unix timestamp in microseconds
- };
-
- public const byte MAVLINK_MSG_ID_PING_LEN = 14;
- public const byte MAVLINK_MSG_ID_POSITION_TARGET = 63;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_position_target_t
- {
- public float x; /// x position
- public float y; /// y position
- public float z; /// z position
- public float yaw; /// yaw orientation in radians, 0 = NORTH
- };
-
- public const byte MAVLINK_MSG_ID_POSITION_TARGET_LEN = 16;
- public const byte MAVLINK_MSG_ID_RAW_IMU = 28;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_raw_imu_t
- {
- public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public short xacc; /// X acceleration (raw)
- public short yacc; /// Y acceleration (raw)
- public short zacc; /// Z acceleration (raw)
- public short xgyro; /// Angular speed around X axis (raw)
- public short ygyro; /// Angular speed around Y axis (raw)
- public short zgyro; /// Angular speed around Z axis (raw)
- public short xmag; /// X Magnetic field (raw)
- public short ymag; /// Y Magnetic field (raw)
- public short zmag; /// Z Magnetic field (raw)
- };
-
- public const byte MAVLINK_MSG_ID_RAW_IMU_LEN = 26;
- public const byte MAVLINK_MSG_ID_RAW_PRESSURE = 29;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_raw_pressure_t
- {
- public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public short press_abs; /// Absolute pressure (raw)
- public short press_diff1; /// Differential pressure 1 (raw)
- public short press_diff2; /// Differential pressure 2 (raw)
- public short temperature; /// Raw Temperature measurement (raw)
- };
-
- public const byte MAVLINK_MSG_ID_RAW_PRESSURE_LEN = 16;
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_rc_channels_override_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public ushort chan1_raw; /// RC channel 1 value, in microseconds
- public ushort chan2_raw; /// RC channel 2 value, in microseconds
- public ushort chan3_raw; /// RC channel 3 value, in microseconds
- public ushort chan4_raw; /// RC channel 4 value, in microseconds
- public ushort chan5_raw; /// RC channel 5 value, in microseconds
- public ushort chan6_raw; /// RC channel 6 value, in microseconds
- public ushort chan7_raw; /// RC channel 7 value, in microseconds
- public ushort chan8_raw; /// RC channel 8 value, in microseconds
- };
-
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN = 18;
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_rc_channels_raw_t
- {
- public ushort chan1_raw; /// RC channel 1 value, in microseconds
- public ushort chan2_raw; /// RC channel 2 value, in microseconds
- public ushort chan3_raw; /// RC channel 3 value, in microseconds
- public ushort chan4_raw; /// RC channel 4 value, in microseconds
- public ushort chan5_raw; /// RC channel 5 value, in microseconds
- public ushort chan6_raw; /// RC channel 6 value, in microseconds
- public ushort chan7_raw; /// RC channel 7 value, in microseconds
- public ushort chan8_raw; /// RC channel 8 value, in microseconds
- public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100%
- };
-
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN = 17;
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 36;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_rc_channels_scaled_t
- {
- public short chan1_scaled; /// RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan2_scaled; /// RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan3_scaled; /// RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan4_scaled; /// RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan5_scaled; /// RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan6_scaled; /// RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan7_scaled; /// RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public short chan8_scaled; /// RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
- public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100%
- };
-
- public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN = 17;
- public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_request_data_stream_t
- {
- public byte target_system; /// The target requested to send the message stream.
- public byte target_component; /// The target requested to send the message stream.
- public byte req_stream_id; /// The ID of the requested message type
- public ushort req_message_rate; /// Update rate in Hertz
- public byte start_stop; /// 1 to start sending, 0 to stop sending.
- };
-
- public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN = 6;
- public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 58;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t
- {
- public ulong time_us; /// Timestamp in micro seconds since unix epoch
- public float roll_speed; /// Desired roll angular speed in rad/s
- public float pitch_speed; /// Desired pitch angular speed in rad/s
- public float yaw_speed; /// Desired yaw angular speed in rad/s
- public float thrust; /// Collective thrust, normalized to 0 .. 1
- };
-
- public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN = 24;
- public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 57;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_roll_pitch_yaw_thrust_setpoint_t
- {
- public ulong time_us; /// Timestamp in micro seconds since unix epoch
- public float roll; /// Desired roll angle in radians
- public float pitch; /// Desired pitch angle in radians
- public float yaw; /// Desired yaw angle in radians
- public float thrust; /// Collective thrust, normalized to 0 .. 1
- };
-
- public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN = 24;
- public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 54;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_safety_allowed_area_t
- {
- public byte frame; /// 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 float p1x; /// x position 1 / Latitude 1
- public float p1y; /// y position 1 / Longitude 1
- public float p1z; /// z position 1 / Altitude 1
- public float p2x; /// x position 2 / Latitude 2
- public float p2y; /// y position 2 / Longitude 2
- public float p2z; /// z position 2 / Altitude 2
- };
-
- public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN = 25;
- public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 53;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_safety_set_allowed_area_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte frame; /// 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 float p1x; /// x position 1 / Latitude 1
- public float p1y; /// y position 1 / Longitude 1
- public float p1z; /// z position 1 / Altitude 1
- public float p2x; /// x position 2 / Latitude 2
- public float p2y; /// y position 2 / Longitude 2
- public float p2z; /// z position 2 / Altitude 2
- };
-
- public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN = 27;
- public const byte MAVLINK_MSG_ID_SCALED_IMU = 26;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_scaled_imu_t
- {
- public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public short xacc; /// X acceleration (mg)
- public short yacc; /// Y acceleration (mg)
- public short zacc; /// Z acceleration (mg)
- public short xgyro; /// Angular speed around X axis (millirad /sec)
- public short ygyro; /// Angular speed around Y axis (millirad /sec)
- public short zgyro; /// Angular speed around Z axis (millirad /sec)
- public short xmag; /// X Magnetic field (milli tesla)
- public short ymag; /// Y Magnetic field (milli tesla)
- public short zmag; /// Z Magnetic field (milli tesla)
- };
-
- public const byte MAVLINK_MSG_ID_SCALED_IMU_LEN = 26;
- public const byte MAVLINK_MSG_ID_SCALED_PRESSURE = 38;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_scaled_pressure_t
- {
- public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- public float press_abs; /// Absolute pressure (hectopascal)
- public float press_diff; /// Differential pressure 1 (hectopascal)
- public short temperature; /// Temperature measurement (0.01 degrees celsius)
- };
-
- public const byte MAVLINK_MSG_ID_SCALED_PRESSURE_LEN = 18;
- public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 37;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_servo_output_raw_t
- {
- public ushort servo1_raw; /// Servo output 1 value, in microseconds
- public ushort servo2_raw; /// Servo output 2 value, in microseconds
- public ushort servo3_raw; /// Servo output 3 value, in microseconds
- public ushort servo4_raw; /// Servo output 4 value, in microseconds
- public ushort servo5_raw; /// Servo output 5 value, in microseconds
- public ushort servo6_raw; /// Servo output 6 value, in microseconds
- public ushort servo7_raw; /// Servo output 7 value, in microseconds
- public ushort servo8_raw; /// Servo output 8 value, in microseconds
- };
-
- public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN = 16;
- public const byte MAVLINK_MSG_ID_SET_ALTITUDE = 65;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_altitude_t
- {
- public byte target; /// The system setting the altitude
- public uint mode; /// The new altitude in meters
- };
-
- public const byte MAVLINK_MSG_ID_SET_ALTITUDE_LEN = 5;
- public const byte MAVLINK_MSG_ID_SET_MODE = 11;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_mode_t
- {
- public byte target; /// The system setting the mode
- public byte mode; /// The new mode
- };
-
- public const byte MAVLINK_MSG_ID_SET_MODE_LEN = 2;
- public const byte MAVLINK_MSG_ID_SET_NAV_MODE = 12;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_nav_mode_t
- {
- public byte target; /// The system setting the mode
- public byte nav_mode; /// The new navigation mode
- };
-
- public const byte MAVLINK_MSG_ID_SET_NAV_MODE_LEN = 2;
- public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 56;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_roll_pitch_yaw_speed_thrust_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public float roll_speed; /// Desired roll angular speed in rad/s
- public float pitch_speed; /// Desired pitch angular speed in rad/s
- public float yaw_speed; /// Desired yaw angular speed in rad/s
- public float thrust; /// Collective thrust, normalized to 0 .. 1
- };
-
- public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN = 18;
- public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 55;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_set_roll_pitch_yaw_thrust_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public float roll; /// Desired roll angle in radians
- public float pitch; /// Desired pitch angle in radians
- public float yaw; /// Desired yaw angle in radians
- public float thrust; /// Collective thrust, normalized to 0 .. 1
- };
-
- public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN = 18;
- public const byte MAVLINK_MSG_ID_STATE_CORRECTION = 64;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_state_correction_t
- {
- public float xErr; /// x position error
- public float yErr; /// y position error
- public float zErr; /// z position error
- public float rollErr; /// roll error (radians)
- public float pitchErr; /// pitch error (radians)
- public float yawErr; /// yaw error (radians)
- public float vxErr; /// x velocity
- public float vyErr; /// y velocity
- public float vzErr; /// z velocity
- };
-
- public const byte MAVLINK_MSG_ID_STATE_CORRECTION_LEN = 36;
- public const byte MAVLINK_MSG_ID_STATUSTEXT = 254;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_statustext_t
- {
- public byte severity; /// Severity of status, 0 = info message, 255 = critical fault
- [MarshalAs(
- UnmanagedType.ByValArray,
- SizeConst=50)]
- public byte[] text; /// Status text message, without null termination public byteacter
- };
-
- public const byte MAVLINK_MSG_ID_STATUSTEXT_LEN = 51;
- public const byte MAVLINK_MSG_ID_SYSTEM_TIME = 2;
- public const byte MAVLINK_MSG_ID_SYSTEM_TIME_UTC = 4;
- public const byte MAVLINK_MSG_ID_SYS_STATUS = 34;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_sys_status_t
- {
- public byte mode; /// System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
- public byte nav_mode; /// Navigation mode, see MAV_NAV_MODE ENUM
- public byte status; /// System status flag, see MAV_STATUS ENUM
- public ushort load; /// Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
- public ushort vbat; /// Battery voltage, in millivolts (1 = 1 millivolt)
- public ushort battery_remaining; /// Remaining battery energy: (0%: 0, 100%: 1000)
- public ushort packet_drop; /// Dropped packets (packets that were corrupted on reception on the MAV)
- };
-
- public const byte MAVLINK_MSG_ID_SYS_STATUS_LEN = 11;
- public const byte MAVLINK_MSG_ID_VFR_HUD = 74;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_vfr_hud_t
- {
- public float airspeed; /// Current airspeed in m/s
- public float groundspeed; /// Current ground speed in m/s
- public short heading; /// Current heading in degrees, in compass units (0..360, 0=north)
- public ushort throttle; /// Current throttle setting in integer percent, 0 to 100
- public float alt; /// Current altitude (MSL), in meters
- public float climb; /// Current climb rate in meters/second
- };
-
- public const byte MAVLINK_MSG_ID_VFR_HUD_LEN = 20;
- public const byte MAVLINK_MSG_ID_WAYPOINT = 39;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_waypoint_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public ushort seq; /// Sequence
- public byte frame; /// The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
- public byte command; /// The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
- public byte current; /// false:0, true:1
- public byte autocontinue; /// autocontinue to next wp
- public float param1; /// PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
- public float param2; /// PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
- public float param3; /// PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
- public float param4; /// PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
- public float x; /// PARAM5 / local: x position, global: latitude
- public float y; /// PARAM6 / y position: global: longitude
- public float z; /// PARAM7 / z position: global: altitude
- };
-
- public const byte MAVLINK_MSG_ID_WAYPOINT_LEN = 36;
- public const byte MAVLINK_MSG_ID_WAYPOINT_ACK = 47;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_waypoint_ack_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public byte type; /// 0: OK, 1: Error
- };
-
- public const byte MAVLINK_MSG_ID_WAYPOINT_ACK_LEN = 3;
- public const byte MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL = 45;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_waypoint_clear_all_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL_LEN = 2;
- public const byte MAVLINK_MSG_ID_WAYPOINT_COUNT = 44;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_waypoint_count_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public ushort count; /// Number of Waypoints in the Sequence
- };
-
- public const byte MAVLINK_MSG_ID_WAYPOINT_COUNT_LEN = 4;
- public const byte MAVLINK_MSG_ID_WAYPOINT_CURRENT = 42;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_waypoint_current_t
- {
- public ushort seq; /// Sequence
- };
-
- public const byte MAVLINK_MSG_ID_WAYPOINT_CURRENT_LEN = 2;
- public const byte MAVLINK_MSG_ID_WAYPOINT_REACHED = 46;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_waypoint_reached_t
- {
- public ushort seq; /// Sequence
- };
-
- public const byte MAVLINK_MSG_ID_WAYPOINT_REACHED_LEN = 2;
- public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST = 40;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_waypoint_request_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public ushort seq; /// Sequence
- };
-
- public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN = 4;
- public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST = 43;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_waypoint_request_list_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- };
-
- public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST_LEN = 2;
- public const byte MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT = 41;
- [StructLayout(LayoutKind.Sequential,Pack=1)]
- public struct __mavlink_waypoint_set_current_t
- {
- public byte target_system; /// System ID
- public byte target_component; /// Component ID
- public ushort seq; /// Sequence
- };
-
- public const byte MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT_LEN = 4;
- public enum MAV_CLASS
+ public const string MAVLINK_BUILD_DATE = "Wed Apr 4 18:13:05 2012";
+ public const string MAVLINK_WIRE_PROTOCOL_VERSION = "0.9";
+ public const int MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 42;
+
+ public const int MAVLINK_LITTLE_ENDIAN = 1;
+ public const int MAVLINK_BIG_ENDIAN = 0;
+
+ public const byte MAVLINK_STX = 85;
+
+ public const byte MAVLINK_ENDIAN = MAVLINK_BIG_ENDIAN;
+
+ public const bool MAVLINK_ALIGNED_FIELDS = (0 == 1);
+
+ public const byte MAVLINK_CRC_EXTRA = 0;
+
+ public const bool MAVLINK_NEED_BYTE_SWAP = (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN);
+
+ public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5};
+
+ public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 127, 42, 21, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7};
+
+ public Type[] MAVLINK_MESSAGE_INFO = new Type[] {typeof( mavlink_heartbeat_t ), typeof( mavlink_boot_t ), typeof( mavlink_system_time_t ), typeof( mavlink_ping_t ), typeof( mavlink_system_time_utc_t ), typeof( mavlink_change_operator_control_t ), typeof( mavlink_change_operator_control_ack_t ), typeof( mavlink_auth_key_t ), null, typeof( mavlink_action_ack_t ), typeof( mavlink_action_t ), typeof( mavlink_set_mode_t ), typeof( mavlink_set_nav_mode_t ), 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 ), null, typeof( mavlink_gps_raw_int_t ), typeof( mavlink_scaled_imu_t ), typeof( mavlink_gps_status_t ), typeof( mavlink_raw_imu_t ), typeof( mavlink_raw_pressure_t ), typeof( mavlink_attitude_t ), typeof( mavlink_local_position_t ), typeof( mavlink_gps_raw_t ), typeof( mavlink_global_position_t ), typeof( mavlink_sys_status_t ), typeof( mavlink_rc_channels_raw_t ), typeof( mavlink_rc_channels_scaled_t ), typeof( mavlink_servo_output_raw_t ), typeof( mavlink_scaled_pressure_t ), typeof( mavlink_waypoint_t ), typeof( mavlink_waypoint_request_t ), typeof( mavlink_waypoint_set_current_t ), typeof( mavlink_waypoint_current_t ), typeof( mavlink_waypoint_request_list_t ), typeof( mavlink_waypoint_count_t ), typeof( mavlink_waypoint_clear_all_t ), typeof( mavlink_waypoint_reached_t ), typeof( mavlink_waypoint_ack_t ), typeof( mavlink_gps_set_global_origin_t ), typeof( mavlink_gps_local_origin_set_t ), typeof( mavlink_local_position_setpoint_set_t ), typeof( mavlink_local_position_setpoint_t ), typeof( mavlink_control_status_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 ), null, null, null, typeof( mavlink_nav_controller_output_t ), typeof( mavlink_position_target_t ), typeof( mavlink_state_correction_t ), typeof( mavlink_set_altitude_t ), typeof( mavlink_request_data_stream_t ), typeof( mavlink_hil_state_t ), typeof( mavlink_hil_controls_t ), typeof( mavlink_manual_control_t ), typeof( mavlink_rc_channels_override_t ), null, null, typeof( mavlink_global_position_int_t ), typeof( mavlink_vfr_hud_t ), typeof( mavlink_command_t ), typeof( mavlink_command_ack_t ), 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_optical_flow_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, typeof( mavlink_object_detection_event_t ), 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 ), 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, null, null, null, null, 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 )};
+
+ 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,
+
+ };
+
+ /** @brief */
+ public enum MAV_CMD
+ {
+ /// Navigate to waypoint. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the waypoint 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 waypoint (rotary wing)| Latitude| Longitude| Altitude|
+ WAYPOINT=16,
+ /// Loiter around this waypoint an unlimited amount of time |Empty| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|
+ LOITER_UNLIM=17,
+ /// Loiter around this waypoint for X turns |Turns| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|
+ LOITER_TURNS=18,
+ /// Loiter around this waypoint for X seconds |Seconds (decimal)| Empty| Radius around waypoint, 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)| Waypoint 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 capturing. |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,
+ /// 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 devices such as cameras. |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
+ DO_SET_ROI=201,
+ /// 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,
+ /// 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,
+ /// |
+ ENUM_END=246,
+
+ };
+
+ /** @brief */
+ public enum FENCE_ACTION
+ {
+ /// Disable fenced mode |
+ NONE=0,
+ /// Switched to guided mode to return point (fence point 0) |
+ GUIDED=1,
+ /// |
+ ENUM_END=2,
+
+ };
+
+ /** @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,
+
+ };
+
+
+
+ public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS = 150;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)]
+ public struct mavlink_sensor_offsets_t
+ {
+ /// magnetometer X offset
+ public Int16 mag_ofs_x;
+ /// magnetometer Y offset
+ public Int16 mag_ofs_y;
+ /// magnetometer Z offset
+ public Int16 mag_ofs_z;
+ /// magnetic declination (radians)
+ public Single mag_declination;
+ /// raw pressure from barometer
+ public Int32 raw_press;
+ /// raw temperature from barometer
+ public Int32 raw_temp;
+ /// gyro X calibration
+ public Single gyro_cal_x;
+ /// gyro Y calibration
+ public Single gyro_cal_y;
+ /// gyro Z calibration
+ public Single gyro_cal_z;
+ /// accel X calibration
+ public Single accel_cal_x;
+ /// accel Y calibration
+ public Single accel_cal_y;
+ /// accel Z calibration
+ public Single accel_cal_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
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// magnetometer X offset
+ public Int16 mag_ofs_x;
+ /// magnetometer Y offset
+ public Int16 mag_ofs_y;
+ /// magnetometer Z offset
+ public Int16 mag_ofs_z;
+
+ };
+
+
+ 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 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;
+ /// ADC output 3
+ public UInt16 adc3;
+ /// ADC output 4
+ public UInt16 adc4;
+ /// ADC output 5
+ public UInt16 adc5;
+ /// ADC output 6
+ 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
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
+ public byte mode;
+ /// Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
+ public UInt16 shutter_speed;
+ /// F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
+ public byte aperture;
+ /// ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
+ public byte iso;
+ /// Exposure type enumeration from 1 to N (0 means ignore)
+ 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;
+ /// Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
+ public byte engine_cut_off;
+ /// Extra parameters enumeration (0 means ignore)
+ public byte extra_param;
+ /// 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
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
+ public byte session;
+ /// 1 to N //Zoom's absolute position (0 means ignore)
+ public byte zoom_pos;
+ /// -100 to 100 //Zooming step value to offset zoom from the current position
+ public byte zoom_step;
+ /// 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
+ public byte focus_lock;
+ /// 0: ignore, 1: shot or start filming
+ 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;
+ /// Extra parameters enumeration (0 means ignore)
+ public byte extra_param;
+ /// Correspondent value to given extra_param
+ public Single extra_value;
+
+ };
+
+
+ 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;
+ /// mount operating mode (see MAV_MOUNT_MODE enum)
+ public byte mount_mode;
+ /// (1 = yes, 0 = no)
+ public byte stab_roll;
+ /// (1 = yes, 0 = no)
+ public byte stab_pitch;
+ /// (1 = yes, 0 = no)
+ 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
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// 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;
+ /// yaw(deg*100) or alt (in cm) depending on mount mode
+ public Int32 input_c;
+ /// if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
+ 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
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// 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;
+ /// yaw(deg*100) or alt (in cm) depending on mount mode
+ public Int32 pointing_c;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_FENCE_POINT = 160;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)]
+ public struct mavlink_fence_point_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// point index (first point is 1, 0 is for return point)
+ public byte idx;
+ /// total number of points (for sanity checking)
+ public byte count;
+ /// Latitude of point
+ public Single lat;
+ /// Longitude of point
+ public Single lng;
+
+ };
+
+
+ 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;
+ /// point index (first point is 1, 0 is for return point)
+ 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
+ {
+ /// 0 if currently inside fence, 1 if outside
+ public byte breach_status;
+ /// number of fence breaches
+ public UInt16 breach_count;
+ /// last breach type (see FENCE_BREACH_* enum)
+ public byte breach_type;
+ /// time of last breach in milliseconds since boot
+ public UInt32 breach_time;
+
+ };
+
+
+ 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;
+ /// Z gyro drift estimate rad/s
+ public Single omegaIz;
+ /// average accel_weight
+ public Single accel_weight;
+ /// average renormalisation value
+ public Single renorm_val;
+ /// average error_roll_pitch value
+ public Single error_rp;
+ /// average error_yaw value
+ public Single error_yaw;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SIMSTATE = 164;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
+ public struct mavlink_simstate_t
+ {
+ /// Roll angle (rad)
+ public Single roll;
+ /// Pitch angle (rad)
+ public Single pitch;
+ /// Yaw angle (rad)
+ public Single yaw;
+ /// X acceleration m/s/s
+ public Single xacc;
+ /// Y acceleration m/s/s
+ public Single yacc;
+ /// Z acceleration m/s/s
+ public Single zacc;
+ /// Angular speed around X axis rad/s
+ public Single xgyro;
+ /// Angular speed around Y axis rad/s
+ public Single ygyro;
+ /// Angular speed around Z axis rad/s
+ public Single zgyro;
+
+ };
+
+
+ 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 const byte MAVLINK_MSG_ID_RADIO = 166;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)]
+ public struct mavlink_radio_t
+ {
+ /// local signal strength
+ public byte rssi;
+ /// remote signal strength
+ public byte remrssi;
+ /// how full the tx buffer is as a percentage
+ public byte txbuf;
+ /// receive errors
+ public UInt16 rxerrors;
+ /// serial errors
+ public UInt16 serrors;
+ /// count of error corrected packets
+ public UInt16 fixedp;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_HEARTBEAT = 0;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+ public struct mavlink_heartbeat_t
+ {
+ /// Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+ public byte type;
+ /// Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
+ public byte autopilot;
+ /// MAVLink version
+ public byte mavlink_version;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_BOOT = 1;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+ public struct mavlink_boot_t
+ {
+ /// The onboard software version
+ public UInt32 version;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SYSTEM_TIME = 2;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+ public struct mavlink_system_time_t
+ {
+ /// Timestamp of the master clock in microseconds since UNIX epoch.
+ public UInt64 time_usec;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_PING = 3;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+ public struct mavlink_ping_t
+ {
+ /// PING sequence
+ 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;
+ /// 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;
+ /// Unix timestamp in microseconds
+ public UInt64 time;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SYSTEM_TIME_UTC = 4;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+ public struct mavlink_system_time_utc_t
+ {
+ /// GPS UTC date ddmmyy
+ public UInt32 utc_date;
+ /// GPS UTC time hhmmss
+ public UInt32 utc_time;
+
+ };
+
+
+ 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;
+ /// 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;
+ /// 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 string 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;
+ /// 0: request control of this MAV, 1: Release control of this MAV
+ 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 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 string key;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_ACTION_ACK = 9;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+ public struct mavlink_action_ack_t
+ {
+ /// The action id
+ public byte action;
+ /// 0: Action DENIED, 1: Action executed
+ public byte result;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_ACTION = 10;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+ public struct mavlink_action_t
+ {
+ /// The system executing the action
+ public byte target;
+ /// The component executing the action
+ public byte target_component;
+ /// The action id
+ public byte action;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SET_MODE = 11;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+ public struct mavlink_set_mode_t
+ {
+ /// The system setting the mode
+ public byte target;
+ /// The new mode
+ public byte mode;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SET_NAV_MODE = 12;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+ public struct mavlink_set_nav_mode_t
+ {
+ /// The system setting the mode
+ public byte target;
+ /// The new navigation mode
+ public byte nav_mode;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=19)]
+ public struct mavlink_param_request_read_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// Onboard parameter id
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=15)]
+ public byte[] param_id;
+ /// Parameter index. Send -1 to use the param ID field as identifier
+ public Int16 param_index;
+
+ };
+
+
+ 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 const byte MAVLINK_MSG_ID_PARAM_VALUE = 22;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)]
+ public struct mavlink_param_value_t
+ {
+ /// Onboard parameter id
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=15)]
+ public byte[] param_id;
+ /// Onboard parameter value
+ public Single param_value;
+ /// Total number of onboard parameters
+ public UInt16 param_count;
+ /// Index of this onboard parameter
+ public UInt16 param_index;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_PARAM_SET = 23;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=21)]
+ public struct mavlink_param_set_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// Onboard parameter id
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=15)]
+ public byte[] param_id;
+ /// Onboard parameter value
+ public Single param_value;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_GPS_RAW_INT = 25;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)]
+ public struct mavlink_gps_raw_int_t
+ {
+ /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ public UInt64 usec;
+ /// 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;
+ /// Latitude in 1E7 degrees
+ public Int32 lat;
+ /// Longitude in 1E7 degrees
+ public Int32 lon;
+ /// Altitude in 1E3 meters (millimeters)
+ public Int32 alt;
+ /// GPS HDOP
+ public Single eph;
+ /// GPS VDOP
+ public Single epv;
+ /// GPS ground speed (m/s)
+ public Single v;
+ /// Compass heading in degrees, 0..360 degrees
+ public Single hdg;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SCALED_IMU = 26;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)]
+ public struct mavlink_scaled_imu_t
+ {
+ /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ public UInt64 usec;
+ /// X acceleration (mg)
+ public Int16 xacc;
+ /// Y acceleration (mg)
+ public Int16 yacc;
+ /// Z acceleration (mg)
+ public Int16 zacc;
+ /// Angular speed around X axis (millirad /sec)
+ public Int16 xgyro;
+ /// Angular speed around Y axis (millirad /sec)
+ public Int16 ygyro;
+ /// Angular speed around Z axis (millirad /sec)
+ public Int16 zgyro;
+ /// X Magnetic field (milli tesla)
+ public Int16 xmag;
+ /// Y Magnetic field (milli tesla)
+ public Int16 ymag;
+ /// Z Magnetic field (milli tesla)
+ public Int16 zmag;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_GPS_STATUS = 27;
+ [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;
+ /// 0: Satellite not used, 1: used for localization
+ [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;
+ /// Direction of satellite, 0: 0 deg, 255: 360 deg.
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+ public byte[] satellite_azimuth;
+ /// Signal to noise ratio of satellite
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+ public byte[] satellite_snr;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_RAW_IMU = 28;
+ [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 usec;
+ /// X acceleration (raw)
+ public Int16 xacc;
+ /// Y acceleration (raw)
+ public Int16 yacc;
+ /// Z acceleration (raw)
+ public Int16 zacc;
+ /// Angular speed around X axis (raw)
+ public Int16 xgyro;
+ /// Angular speed around Y axis (raw)
+ public Int16 ygyro;
+ /// Angular speed around Z axis (raw)
+ public Int16 zgyro;
+ /// X Magnetic field (raw)
+ public Int16 xmag;
+ /// Y Magnetic field (raw)
+ public Int16 ymag;
+ /// Z Magnetic field (raw)
+ public Int16 zmag;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_RAW_PRESSURE = 29;
+ [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 usec;
+ /// Absolute pressure (raw)
+ public Int16 press_abs;
+ /// Differential pressure 1 (raw)
+ public Int16 press_diff1;
+ /// Differential pressure 2 (raw)
+ public Int16 press_diff2;
+ /// Raw Temperature measurement (raw)
+ public Int16 temperature;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SCALED_PRESSURE = 38;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+ public struct mavlink_scaled_pressure_t
+ {
+ /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ public UInt64 usec;
+ /// Absolute pressure (hectopascal)
+ public Single press_abs;
+ /// Differential pressure 1 (hectopascal)
+ public Single press_diff;
+ /// Temperature measurement (0.01 degrees celsius)
+ public Int16 temperature;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_ATTITUDE = 30;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+ public struct mavlink_attitude_t
+ {
+ /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ public UInt64 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;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_LOCAL_POSITION = 31;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+ public struct mavlink_local_position_t
+ {
+ /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ public UInt64 usec;
+ /// X Position
+ public Single x;
+ /// Y Position
+ public Single y;
+ /// Z Position
+ public Single z;
+ /// X Speed
+ public Single vx;
+ /// Y Speed
+ public Single vy;
+ /// Z Speed
+ public Single vz;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_GLOBAL_POSITION = 33;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+ public struct mavlink_global_position_t
+ {
+ /// Timestamp (microseconds since unix epoch)
+ public UInt64 usec;
+ /// Latitude, in degrees
+ public Single lat;
+ /// Longitude, in degrees
+ public Single lon;
+ /// Absolute altitude, in meters
+ public Single alt;
+ /// X Speed (in Latitude direction, positive: going north)
+ public Single vx;
+ /// Y Speed (in Longitude direction, positive: going east)
+ public Single vy;
+ /// Z Speed (in Altitude direction, positive: going up)
+ public Single vz;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_GPS_RAW = 32;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)]
+ public struct mavlink_gps_raw_t
+ {
+ /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ public UInt64 usec;
+ /// 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;
+ /// Latitude in degrees
+ public Single lat;
+ /// Longitude in degrees
+ public Single lon;
+ /// Altitude in meters
+ public Single alt;
+ /// GPS HDOP
+ public Single eph;
+ /// GPS VDOP
+ public Single epv;
+ /// GPS ground speed
+ public Single v;
+ /// Compass heading in degrees, 0..360 degrees
+ public Single hdg;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SYS_STATUS = 34;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=11)]
+ public struct mavlink_sys_status_t
+ {
+ /// System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
+ public byte mode;
+ /// Navigation mode, see MAV_NAV_MODE ENUM
+ public byte nav_mode;
+ /// System status flag, see MAV_STATUS ENUM
+ public byte status;
+ /// Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ public UInt16 load;
+ /// Battery voltage, in millivolts (1 = 1 millivolt)
+ public UInt16 vbat;
+ /// Remaining battery energy: (0%: 0, 100%: 1000)
+ public UInt16 battery_remaining;
+ /// Dropped packets (packets that were corrupted on reception on the MAV)
+ public UInt16 packet_drop;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)]
+ public struct mavlink_rc_channels_raw_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;
+ /// Receive signal strength indicator, 0: 0%, 255: 100%
+ public byte rssi;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 36;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)]
+ public struct mavlink_rc_channels_scaled_t
+ {
+ /// RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan1_scaled;
+ /// RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan2_scaled;
+ /// RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan3_scaled;
+ /// RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan4_scaled;
+ /// RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan5_scaled;
+ /// RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan6_scaled;
+ /// RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan7_scaled;
+ /// RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
+ public Int16 chan8_scaled;
+ /// Receive signal strength indicator, 0: 0%, 255: 100%
+ public byte rssi;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 37;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)]
+ public struct mavlink_servo_output_raw_t
+ {
+ /// Servo output 1 value, in microseconds
+ public UInt16 servo1_raw;
+ /// Servo output 2 value, in microseconds
+ public UInt16 servo2_raw;
+ /// Servo output 3 value, in microseconds
+ public UInt16 servo3_raw;
+ /// Servo output 4 value, in microseconds
+ public UInt16 servo4_raw;
+ /// Servo output 5 value, in microseconds
+ public UInt16 servo5_raw;
+ /// Servo output 6 value, in microseconds
+ public UInt16 servo6_raw;
+ /// Servo output 7 value, in microseconds
+ public UInt16 servo7_raw;
+ /// Servo output 8 value, in microseconds
+ public UInt16 servo8_raw;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_WAYPOINT = 39;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
+ public struct mavlink_waypoint_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// Sequence
+ public UInt16 seq;
+ /// The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
+ public byte frame;
+ /// The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
+ public byte command;
+ /// false:0, true:1
+ public byte current;
+ /// autocontinue to next wp
+ public byte autocontinue;
+ /// PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
+ public Single param1;
+ /// PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
+ public Single param2;
+ /// PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
+ public Single param3;
+ /// PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
+ public Single param4;
+ /// PARAM5 / local: x position, global: latitude
+ public Single x;
+ /// PARAM6 / y position: global: longitude
+ public Single y;
+ /// PARAM7 / z position: global: altitude
+ public Single z;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST = 40;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+ public struct mavlink_waypoint_request_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// Sequence
+ public UInt16 seq;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT = 41;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+ public struct mavlink_waypoint_set_current_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// Sequence
+ public UInt16 seq;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_WAYPOINT_CURRENT = 42;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+ public struct mavlink_waypoint_current_t
+ {
+ /// Sequence
+ public UInt16 seq;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST = 43;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+ public struct mavlink_waypoint_request_list_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_WAYPOINT_COUNT = 44;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+ public struct mavlink_waypoint_count_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// Number of Waypoints in the Sequence
+ public UInt16 count;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL = 45;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+ public struct mavlink_waypoint_clear_all_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_WAYPOINT_REACHED = 46;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+ public struct mavlink_waypoint_reached_t
+ {
+ /// Sequence
+ public UInt16 seq;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_WAYPOINT_ACK = 47;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+ public struct mavlink_waypoint_ack_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// 0: OK, 1: Error
+ public byte type;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN = 48;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+ public struct mavlink_gps_set_global_origin_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// global position * 1E7
+ public Int32 latitude;
+ /// global position * 1E7
+ public Int32 longitude;
+ /// global position * 1000
+ public Int32 altitude;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET = 49;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)]
+ public struct mavlink_gps_local_origin_set_t
+ {
+ /// Latitude (WGS84), expressed as * 1E7
+ public Int32 latitude;
+ /// Longitude (WGS84), expressed as * 1E7
+ public Int32 longitude;
+ /// Altitude(WGS84), expressed as * 1000
+ public Int32 altitude;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET = 50;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+ public struct mavlink_local_position_setpoint_set_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// x position
+ public Single x;
+ /// y position
+ public Single y;
+ /// z position
+ public Single z;
+ /// Desired yaw angle
+ public Single yaw;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)]
+ public struct mavlink_local_position_setpoint_t
+ {
+ /// x position
+ public Single x;
+ /// y position
+ public Single y;
+ /// z position
+ public Single z;
+ /// Desired yaw angle
+ public Single yaw;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_CONTROL_STATUS = 52;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+ public struct mavlink_control_status_t
+ {
+ /// Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
+ public byte position_fix;
+ /// Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
+ public byte vision_fix;
+ /// GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
+ public byte gps_fix;
+ /// Attitude estimation health: 0: poor, 255: excellent
+ public byte ahrs_health;
+ /// 0: Attitude control disabled, 1: enabled
+ public byte control_att;
+ /// 0: X, Y position control disabled, 1: enabled
+ public byte control_pos_xy;
+ /// 0: Z position control disabled, 1: enabled
+ public byte control_pos_z;
+ /// 0: Yaw angle control disabled, 1: enabled
+ public byte control_pos_yaw;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 53;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=27)]
+ public struct mavlink_safety_set_allowed_area_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ 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;
+ /// x position 1 / Latitude 1
+ public Single p1x;
+ /// y position 1 / Longitude 1
+ public Single p1y;
+ /// z position 1 / Altitude 1
+ public Single p1z;
+ /// x position 2 / Latitude 2
+ public Single p2x;
+ /// y position 2 / Longitude 2
+ public Single p2y;
+ /// z position 2 / Altitude 2
+ public Single p2z;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 54;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=25)]
+ public struct mavlink_safety_allowed_area_t
+ {
+ /// 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;
+ /// x position 1 / Latitude 1
+ public Single p1x;
+ /// y position 1 / Longitude 1
+ public Single p1y;
+ /// z position 1 / Altitude 1
+ public Single p1z;
+ /// x position 2 / Latitude 2
+ public Single p2x;
+ /// y position 2 / Longitude 2
+ public Single p2y;
+ /// z position 2 / Altitude 2
+ public Single p2z;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 55;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+ public struct mavlink_set_roll_pitch_yaw_thrust_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// 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_SET_ROLL_PITCH_YAW_SPEED_THRUST = 56;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+ public struct mavlink_set_roll_pitch_yaw_speed_thrust_t
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// 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_ROLL_PITCH_YAW_THRUST_SETPOINT = 57;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)]
+ public struct mavlink_roll_pitch_yaw_thrust_setpoint_t
+ {
+ /// Timestamp in micro seconds since unix epoch
+ public UInt64 time_us;
+ /// 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_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 58;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)]
+ public struct mavlink_roll_pitch_yaw_speed_thrust_setpoint_t
+ {
+ /// Timestamp in micro seconds since unix epoch
+ public UInt64 time_us;
+ /// 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_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 desired heading in degrees
+ public Int16 nav_bearing;
+ /// Bearing to current waypoint/target in degrees
+ public Int16 target_bearing;
+ /// Distance to active waypoint in meters
+ public UInt16 wp_dist;
+ /// 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;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_POSITION_TARGET = 63;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)]
+ public struct mavlink_position_target_t
+ {
+ /// x position
+ public Single x;
+ /// y position
+ public Single y;
+ /// z position
+ public Single z;
+ /// yaw orientation in radians, 0 = NORTH
+ public Single yaw;
+
+ };
+
+
+ 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_SET_ALTITUDE = 65;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)]
+ public struct mavlink_set_altitude_t
+ {
+ /// The system setting the altitude
+ public byte target;
+ /// The new altitude in meters
+ public UInt32 mode;
+
+ };
+
+
+ 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 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 message type
+ public byte req_stream_id;
+ /// Update rate in Hertz
+ public UInt16 req_message_rate;
+ /// 1 to start sending, 0 to stop sending.
+ public byte start_stop;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_HIL_STATE = 67;
+ [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 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 = 68;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)]
+ public struct mavlink_hil_controls_t
+ {
+ /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ public UInt64 time_us;
+ /// Control output -3 .. 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;
+ /// System mode (MAV_MODE)
+ public byte mode;
+ /// Navigation mode (MAV_NAV_MODE)
+ public byte nav_mode;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_MANUAL_CONTROL = 69;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=21)]
+ public struct mavlink_manual_control_t
+ {
+ /// The system to be controlled
+ public byte target;
+ /// roll
+ public Single roll;
+ /// pitch
+ public Single pitch;
+ /// yaw
+ public Single yaw;
+ /// thrust
+ public Single thrust;
+ /// 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
+ {
+ /// System ID
+ public byte target_system;
+ /// Component ID
+ public byte target_component;
+ /// 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 const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 73;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+ public struct mavlink_global_position_int_t
+ {
+ /// 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;
+
+ };
+
+
+ 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 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;
+ /// Current altitude (MSL), in meters
+ public Single alt;
+ /// Current climb rate in meters/second
+ public Single climb;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_COMMAND = 75;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)]
+ public struct mavlink_command_t
+ {
+ /// System which should execute the command
+ public byte target_system;
+ /// Component which should execute the command, 0 for all components
+ public byte target_component;
+ /// Command ID, as defined by MAV_CMD enum.
+ public byte command;
+ /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
+ public byte confirmation;
+ /// 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;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_COMMAND_ACK = 76;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+ public struct mavlink_command_ack_t
+ {
+ /// Current airspeed in m/s
+ public Single command;
+ /// 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
+ public Single result;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_OPTICAL_FLOW = 100;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+ public struct mavlink_optical_flow_t
+ {
+ /// Timestamp (UNIX)
+ public UInt64 time;
+ /// Sensor ID
+ public byte sensor_id;
+ /// Flow in pixels in x-sensor direction
+ public Int16 flow_x;
+ /// Flow in pixels in y-sensor direction
+ public Int16 flow_y;
+ /// Optical flow quality / confidence. 0: bad, 255: maximum quality
+ public byte quality;
+ /// Ground distance in meters
+ public Single ground_distance;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT = 140;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
+ public struct mavlink_object_detection_event_t
+ {
+ /// Timestamp in milliseconds since system boot
+ public UInt32 time;
+ /// Object ID
+ public UInt16 object_id;
+ /// Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
+ public byte type;
+ /// Name of the object as defined by the detector
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+ public string name;
+ /// Detection quality / confidence. 0: bad, 255: maximum confidence
+ public byte quality;
+ /// Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
+ public Single bearing;
+ /// Ground distance in meters
+ public Single distance;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_DEBUG_VECT = 251;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=30)]
+ public struct mavlink_debug_vect_t
+ {
+ /// Name
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+ public string name;
+ /// Timestamp
+ public UInt64 usec;
+ /// x
+ public Single x;
+ /// y
+ public Single y;
+ /// z
+ public Single z;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 252;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+ public struct mavlink_named_value_float_t
+ {
+ /// Name of the debug variable
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+ public string name;
+ /// Floating point value
+ public Single value;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT = 253;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+ public struct mavlink_named_value_int_t
+ {
+ /// Name of the debug variable
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+ public string name;
+ /// Signed integer value
+ public Int32 value;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_STATUSTEXT = 254;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=51)]
+ public struct mavlink_statustext_t
+ {
+ /// Severity of status, 0 = info message, 255 = critical fault
+ public byte severity;
+ /// Status text message, without null termination character
+ [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)]
+ public byte[] text;
+
+ };
+
+
+ public const byte MAVLINK_MSG_ID_DEBUG = 255;
+ [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)]
+ public struct mavlink_debug_t
+ {
+ /// index of debug variable
+ public byte ind;
+ /// DEBUG value
+ public Single value; };
+public enum MAV_CLASS
{
MAV_CLASS_GENERIC = 0, /// Generic autopilot, full support for everything
MAV_CLASS_PIXHAWK = 1, /// PIXHAWK autopilot, http://pixhawk.ethz.ch
@@ -1344,9 +1935,20 @@ namespace ArdupilotMega
MAV_FRAME_LOCAL_ENU = 4
};
-Type[] mavstructs = new Type[] {typeof( __mavlink_heartbeat_t) ,typeof( __mavlink_boot_t) ,null ,typeof( __mavlink_ping_t) ,null ,typeof( __mavlink_change_operator_control_t) ,typeof( __mavlink_change_operator_control_ack_t) ,typeof( __mavlink_auth_key_t) ,null ,typeof( __mavlink_action_ack_t) ,typeof( __mavlink_action_t) ,typeof( __mavlink_set_mode_t) ,typeof( __mavlink_set_nav_mode_t) ,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) ,null ,typeof( __mavlink_gps_raw_int_t) ,typeof( __mavlink_scaled_imu_t) ,typeof( __mavlink_gps_status_t) ,typeof( __mavlink_raw_imu_t) ,typeof( __mavlink_raw_pressure_t) ,typeof( __mavlink_attitude_t) ,typeof( __mavlink_local_position_t) ,typeof( __mavlink_gps_raw_t) ,typeof( __mavlink_global_position_t) ,typeof( __mavlink_sys_status_t) ,typeof( __mavlink_rc_channels_raw_t) ,typeof( __mavlink_rc_channels_scaled_t) ,typeof( __mavlink_servo_output_raw_t) ,typeof( __mavlink_scaled_pressure_t) ,typeof( __mavlink_waypoint_t) ,typeof( __mavlink_waypoint_request_t) ,typeof( __mavlink_waypoint_set_current_t) ,typeof( __mavlink_waypoint_current_t) ,typeof( __mavlink_waypoint_request_list_t) ,typeof( __mavlink_waypoint_count_t) ,typeof( __mavlink_waypoint_clear_all_t) ,typeof( __mavlink_waypoint_reached_t) ,typeof( __mavlink_waypoint_ack_t) ,typeof( __mavlink_gps_set_global_origin_t) ,typeof( __mavlink_gps_local_origin_set_t) ,typeof( __mavlink_local_position_setpoint_set_t) ,typeof( __mavlink_local_position_setpoint_t) ,typeof( __mavlink_control_status_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) ,null ,null ,null ,typeof( __mavlink_nav_controller_output_t) ,typeof( __mavlink_position_target_t) ,typeof( __mavlink_state_correction_t) ,typeof( __mavlink_set_altitude_t) ,typeof( __mavlink_request_data_stream_t) ,typeof( __mavlink_hil_state_t) ,typeof( __mavlink_hil_controls_t) ,typeof( __mavlink_manual_control_t) ,typeof( __mavlink_rc_channels_override_t) ,null ,null ,typeof( __mavlink_global_position_int_t) ,typeof( __mavlink_vfr_hud_t) ,typeof( __mavlink_command_t) ,typeof( __mavlink_command_ack_t) ,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_optical_flow_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 ,typeof( __mavlink_object_detection_event_t) ,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_dcm_t) ,typeof( __mavlink_simstate_t) ,typeof( __mavlink_hwstatus_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 ,null ,null ,null ,null ,null ,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 enum MAV_DATA_STREAM
+ {
+ MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */
+ MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */
+ MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */
+ MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */
+ MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */
+ MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */
+ MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */
+ MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */
+ MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */
+ MAV_DATA_STREAM_ENUM_END=13, /* | */
+ };
- }
+ }
#endif
}
-
diff --git a/Tools/ArdupilotMegaPlanner/MagCalib.cs b/Tools/ArdupilotMegaPlanner/MagCalib.cs
index e94a639932..199bcb4975 100644
--- a/Tools/ArdupilotMegaPlanner/MagCalib.cs
+++ b/Tools/ArdupilotMegaPlanner/MagCalib.cs
@@ -98,9 +98,9 @@ namespace ArdupilotMega
if (packet == null)
continue;
- if (packet.GetType() == typeof(MAVLink.__mavlink_vfr_hud_t))
+ if (packet.GetType() == typeof(MAVLink.mavlink_vfr_hud_t))
{
- if (((MAVLink.__mavlink_vfr_hud_t)packet).throttle >= throttleThreshold)
+ if (((MAVLink.mavlink_vfr_hud_t)packet).throttle >= throttleThreshold)
{
useData = true;
}
@@ -111,35 +111,35 @@ namespace ArdupilotMega
}
- if (packet.GetType() == typeof(MAVLink.__mavlink_sensor_offsets_t))
+ if (packet.GetType() == typeof(MAVLink.mavlink_sensor_offsets_t))
{
offset = new Tuple(
- ((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_x,
- ((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_y,
- ((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_z);
+ ((MAVLink.mavlink_sensor_offsets_t)packet).mag_ofs_x,
+ ((MAVLink.mavlink_sensor_offsets_t)packet).mag_ofs_y,
+ ((MAVLink.mavlink_sensor_offsets_t)packet).mag_ofs_z);
}
- else if (packet.GetType() == typeof(MAVLink.__mavlink_raw_imu_t) && useData)
+ else if (packet.GetType() == typeof(MAVLink.mavlink_raw_imu_t) && useData)
{
int div = 20;
// fox dxf
vertex = new Polyline3dVertex(new Vector3f(
- ((MAVLink.__mavlink_raw_imu_t)packet).xmag - offset.Item1,
- ((MAVLink.__mavlink_raw_imu_t)packet).ymag - offset.Item2,
- ((MAVLink.__mavlink_raw_imu_t)packet).zmag - offset.Item3)
+ ((MAVLink.mavlink_raw_imu_t)packet).xmag - offset.Item1,
+ ((MAVLink.mavlink_raw_imu_t)packet).ymag - offset.Item2,
+ ((MAVLink.mavlink_raw_imu_t)packet).zmag - offset.Item3)
);
vertexes.Add(vertex);
// for old method
- setMinorMax(((MAVLink.__mavlink_raw_imu_t)packet).xmag - offset.Item1, ref minx, ref maxx);
- setMinorMax(((MAVLink.__mavlink_raw_imu_t)packet).ymag - offset.Item2, ref miny, ref maxy);
- setMinorMax(((MAVLink.__mavlink_raw_imu_t)packet).zmag - offset.Item3, ref minz, ref maxz);
+ setMinorMax(((MAVLink.mavlink_raw_imu_t)packet).xmag - offset.Item1, ref minx, ref maxx);
+ setMinorMax(((MAVLink.mavlink_raw_imu_t)packet).ymag - offset.Item2, ref miny, ref maxy);
+ setMinorMax(((MAVLink.mavlink_raw_imu_t)packet).zmag - offset.Item3, ref minz, ref maxz);
// for new lease sq
- string item = (int)(((MAVLink.__mavlink_raw_imu_t)packet).xmag / div) + "," +
- (int)(((MAVLink.__mavlink_raw_imu_t)packet).ymag / div) + "," +
- (int)(((MAVLink.__mavlink_raw_imu_t)packet).zmag / div);
+ string item = (int)(((MAVLink.mavlink_raw_imu_t)packet).xmag / div) + "," +
+ (int)(((MAVLink.mavlink_raw_imu_t)packet).ymag / div) + "," +
+ (int)(((MAVLink.mavlink_raw_imu_t)packet).zmag / div);
if (filter.ContainsKey(item))
{
@@ -155,9 +155,9 @@ namespace ArdupilotMega
data.Add(new Tuple(
- ((MAVLink.__mavlink_raw_imu_t)packet).xmag - offset.Item1,
- ((MAVLink.__mavlink_raw_imu_t)packet).ymag - offset.Item2,
- ((MAVLink.__mavlink_raw_imu_t)packet).zmag - offset.Item3));
+ ((MAVLink.mavlink_raw_imu_t)packet).xmag - offset.Item1,
+ ((MAVLink.mavlink_raw_imu_t)packet).ymag - offset.Item2,
+ ((MAVLink.mavlink_raw_imu_t)packet).zmag - offset.Item3));
}
diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs
index 6de12700b3..76ee48fc34 100644
--- a/Tools/ArdupilotMegaPlanner/MainV2.cs
+++ b/Tools/ArdupilotMegaPlanner/MainV2.cs
@@ -58,6 +58,8 @@ namespace ArdupilotMega
bool serialThread = false;
+ static internal BindingSource bs;
+
TcpListener listener;
DateTime heatbeatSend = DateTime.Now;
@@ -187,7 +189,6 @@ namespace ArdupilotMega
if (config["MainWidth"] != null)
this.Width = int.Parse(config["MainWidth"].ToString());
-
if (config["CMB_rateattitude"] != null)
MainV2.cs.rateattitude = byte.Parse(config["CMB_rateattitude"].ToString());
if (config["rateposition"] != null)
@@ -794,7 +795,7 @@ namespace ArdupilotMega
if (joystick != null && joystick.enabled)
{
- MAVLink.__mavlink_rc_channels_override_t rc = new MAVLink.__mavlink_rc_channels_override_t();
+ MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
rc.target_component = comPort.compid;
rc.target_system = comPort.sysid;
@@ -956,7 +957,7 @@ namespace ArdupilotMega
{
// Console.WriteLine("remote lost {0}", cs.packetdropremote);
- MAVLink.__mavlink_heartbeat_t htb = new MAVLink.__mavlink_heartbeat_t();
+ MAVLink.mavlink_heartbeat_t htb = new MAVLink.mavlink_heartbeat_t();
#if MAVLINK10
htb.type = (byte)MAVLink.MAV_TYPE.MAV_TYPE_GCS;
@@ -1862,7 +1863,7 @@ namespace ArdupilotMega
}
if (keyData == (Keys.Control | Keys.W)) // test
{
- Form frm = new GCSViews.ConfigurationView.Configuration();
+ Form frm = new GCSViews.ConfigurationView.Setup();
ThemeManager.ApplyThemeTo(frm);
frm.Show();
return true;
@@ -1942,6 +1943,9 @@ namespace ArdupilotMega
if (comPort.rawlogfile != null)
comPort.rawlogfile.Close();
+
+ comPort.logfile = null;
+ comPort.rawlogfile = null;
}
catch { }
diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
index 73f5cfac07..707f84ff7c 100644
--- a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
+++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
@@ -744,7 +744,7 @@ namespace ArdupilotMega
int colorvalue = ColourValues[step % ColourValues.Length];
step++;
- myCurve = zg1.GraphPane.AddCurve(lookforfields[a].Replace("__mavlink_", ""), lists[a], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None);
+ myCurve = zg1.GraphPane.AddCurve(lookforfields[a].Replace("mavlink_", ""), lists[a], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None);
double xMin, xMax, yMin, yMax;
@@ -795,6 +795,12 @@ namespace ArdupilotMega
object data = MavlinkInterface.DebugPacket(packet, false);
+ if (data == null)
+ {
+ log.Info("No info on packet");
+ continue;
+ }
+
Type test = data.GetType();
foreach (var field in test.GetFields())
@@ -890,9 +896,9 @@ namespace ArdupilotMega
PointPairList list = ((PointPairList)this.data[field]);
- PointPairList listx = ((PointPairList)this.data["xmag __mavlink_raw_imu_t"]);
- PointPairList listy = ((PointPairList)this.data["ymag __mavlink_raw_imu_t"]);
- PointPairList listz = ((PointPairList)this.data["zmag __mavlink_raw_imu_t"]);
+ PointPairList listx = ((PointPairList)this.data["xmag mavlink_raw_imu_t"]);
+ PointPairList listy = ((PointPairList)this.data["ymag mavlink_raw_imu_t"]);
+ PointPairList listz = ((PointPairList)this.data["zmag mavlink_raw_imu_t"]);
//(float)Math.Sqrt(Math.Pow(mx, 2) + Math.Pow(my, 2) + Math.Pow(mz, 2));
@@ -949,13 +955,13 @@ namespace ArdupilotMega
int colorvalue = ColourValues[colorStep % ColourValues.Length];
colorStep++;
- myCurve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name.Replace("__mavlink_", ""), (PointPairList)data[((CheckBox)sender).Name], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None);
+ myCurve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name.Replace("mavlink_", ""), (PointPairList)data[((CheckBox)sender).Name], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None);
myCurve.Tag = ((CheckBox)sender).Name;
- if (myCurve.Tag.ToString() == "roll __mavlink_attitude_t" ||
- myCurve.Tag.ToString() == "pitch __mavlink_attitude_t" ||
- myCurve.Tag.ToString() == "yaw __mavlink_attitude_t")
+ if (myCurve.Tag.ToString() == "roll mavlink_attitude_t" ||
+ myCurve.Tag.ToString() == "pitch mavlink_attitude_t" ||
+ myCurve.Tag.ToString() == "yaw mavlink_attitude_t")
{
PointPairList ppl = new PointPairList((PointPairList)data[((CheckBox)sender).Name]);
for (int a = 0; a < ppl.Count; a++)
diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
index 3b70d39505..7d03a402f9 100644
--- a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
+++ b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
@@ -23,100 +23,100 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
+
+
+
-
-
-
+
+
+
-
-
-
+
+
+
-
-
-
+
+
+
-
-
-
-
-
-
+
+
+
+
+
+
-
-
-
+
+
+
-
-
-
-
+
+
+
+
-
-
-
+
+
+
-
-
-
+
+
+
-
-
-
+
+
+
@@ -157,17 +157,17 @@
-
-
-
+
-
+
-
-
-
-
+
+
+
+
+
+
@@ -188,7 +188,7 @@
-
+
17, 17
-
- 17, 17
-
NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area.
diff --git a/Tools/ArdupilotMegaPlanner/Script.cs b/Tools/ArdupilotMegaPlanner/Script.cs
index 60d5ea4fa1..9face19c31 100644
--- a/Tools/ArdupilotMegaPlanner/Script.cs
+++ b/Tools/ArdupilotMegaPlanner/Script.cs
@@ -14,7 +14,7 @@ namespace ArdupilotMega
static Microsoft.Scripting.Hosting.ScriptScope scope;
// keeps history
- MAVLink.__mavlink_rc_channels_override_t rc = new MAVLink.__mavlink_rc_channels_override_t();
+ MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
public Script()
{
diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx
index 0524d1cf2e..078647e4e0 100644
--- a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx
+++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx
@@ -117,1656 +117,15 @@
System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
- groupBoxElevons
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabRadioIn
-
-
- 0
-
-
- CHK_revch3
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabRadioIn
-
-
- 1
-
-
- CHK_revch4
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabRadioIn
-
-
- 2
-
-
- CHK_revch2
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabRadioIn
-
-
- 3
-
-
- CHK_revch1
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabRadioIn
-
-
- 4
-
-
- BUT_Calibrateradio
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabRadioIn
-
-
- 5
-
-
- BAR8
-
-
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabRadioIn
-
-
- 6
-
-
- BAR7
-
-
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabRadioIn
-
-
- 7
-
-
- BAR6
-
-
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabRadioIn
-
-
- 8
-
-
- BAR5
-
-
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabRadioIn
-
-
- 9
-
-
- BARpitch
-
-
- ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabRadioIn
-
-
- 10
-
-
- BARthrottle
-
-
- ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabRadioIn
-
-
- 11
-
-
- BARyaw
-
-
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabRadioIn
-
-
- 12
-
-
- BARroll
-
-
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabRadioIn
-
-
- 13
-
-
-
- 4, 22
-
-
-
- 3, 3, 3, 3
-
-
- 666, 393
-
-
- 0
-
-
- Radio Input
-
-
- tabRadioIn
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- Tabs
-
-
- 0
-
-
- CB_simple6
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 0
-
-
- CB_simple5
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 1
-
-
- CB_simple4
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 2
-
-
- CB_simple3
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 3
-
-
- CB_simple2
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 4
-
-
- CB_simple1
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 5
-
-
- label14
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 6
-
-
- LBL_flightmodepwm
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 7
-
-
- label13
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 8
-
-
- lbl_currentmode
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 9
-
-
- label12
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 10
-
-
- label11
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 11
-
-
- label10
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 12
-
-
- label9
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 13
-
-
- label8
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 14
-
-
- label7
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 15
-
-
- label6
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 16
-
-
- CMB_fmode6
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 17
-
-
- label5
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 18
-
-
- CMB_fmode5
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 19
-
-
- label4
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 20
-
-
- CMB_fmode4
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 21
-
-
- label3
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 22
-
-
- CMB_fmode3
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 23
-
-
- label2
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 24
-
-
- CMB_fmode2
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 25
-
-
- label1
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 26
-
-
- CMB_fmode1
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabModes
-
-
- 27
-
-
- BUT_SaveModes
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabModes
-
-
- 28
-
-
- 4, 22
-
-
- 666, 393
-
-
- 3
-
-
- Modes
-
-
- tabModes
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- Tabs
-
-
- 1
-
-
- BUT_MagCalibration
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabHardware
-
-
- 0
-
-
- label27
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 1
-
-
- CMB_sonartype
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 2
-
-
- CHK_enableoptflow
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 3
-
-
- pictureBox2
-
-
- System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 4
-
-
- linkLabelmagdec
-
-
- System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 5
-
-
- label100
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 6
-
-
- TXT_declination
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 7
-
-
- CHK_enableairspeed
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 8
-
-
- CHK_enablesonar
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 9
-
-
- CHK_enablecompass
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 10
-
-
- pictureBox4
-
-
- System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 11
-
-
- pictureBox3
-
-
- System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 12
-
-
- pictureBox1
-
-
- System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 13
-
-
- 4, 22
-
-
- 3, 3, 3, 3
-
-
- 666, 393
-
-
- 1
-
-
- Hardware
-
-
- tabHardware
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- Tabs
-
-
- 2
-
-
- groupBox4
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabBattery
-
-
- 0
-
-
- label47
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabBattery
-
-
- 1
-
-
- CMB_batmonsensortype
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabBattery
-
-
- 2
-
-
- textBox3
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabBattery
-
-
- 3
-
-
- label29
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabBattery
-
-
- 4
-
-
- label30
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabBattery
-
-
- 5
-
-
- TXT_battcapacity
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabBattery
-
-
- 6
-
-
- CMB_batmontype
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabBattery
-
-
- 7
-
-
- pictureBox5
-
-
- System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabBattery
-
-
- 8
-
-
- 4, 22
-
-
- 2, 2, 2, 2
-
-
- 666, 393
-
-
- 6
-
-
- Battery
-
-
- tabBattery
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- Tabs
-
-
- 3
-
-
- True
-
-
- NoControl
-
-
- 228, 170
-
-
- 212, 13
-
-
- 11
-
-
- Level your plane to set default accel offsets
-
-
- label48
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabArduplane
-
-
- 0
-
-
- NoControl
-
-
- 285, 199
-
-
- 75, 23
-
-
- 10
-
-
- Level
-
-
- BUT_levelplane
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabArduplane
-
-
- 1
-
-
- 4, 22
-
-
- 3, 3, 3, 3
-
-
- 666, 393
-
-
- 7
-
-
- ArduPlane
-
-
- tabArduplane
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- Tabs
-
-
- 4
-
-
- label28
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabArducopter
-
-
- 0
-
-
- label16
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabArducopter
-
-
- 1
-
-
- label15
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabArducopter
-
-
- 2
-
-
- pictureBoxQuadX
-
-
- System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabArducopter
-
-
- 3
-
-
- pictureBoxQuad
-
-
- System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabArducopter
-
-
- 4
-
-
- BUT_levelac2
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabArducopter
-
-
- 5
-
-
- 4, 22
-
-
- 666, 393
-
-
- 2
-
-
- ArduCopter2
-
-
- tabArducopter
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- Tabs
-
-
- 5
-
-
- groupBox5
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 0
-
-
- BUT_HS4save
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabHeli
-
-
- 1
-
-
- BUT_swash_manual
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabHeli
-
-
- 2
-
-
- groupBox3
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 3
-
-
- label44
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 4
-
-
- label43
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 5
-
-
- label42
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 6
-
-
- groupBox2
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 7
-
-
- groupBox1
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 8
-
-
- HS4_TRIM
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 9
-
-
- HS3_TRIM
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 10
-
-
- HS2_TRIM
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 11
-
-
- HS1_TRIM
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 12
-
-
- label39
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 13
-
-
- label38
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 14
-
-
- label37
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 15
-
-
- label36
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 16
-
-
- label26
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 17
-
-
- PIT_MAX
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 18
-
-
- label25
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 19
-
-
- ROL_MAX
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 20
-
-
- label23
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 21
-
-
- label22
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 22
-
-
- HS4_REV
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 23
-
-
- label20
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 24
-
-
- label19
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 25
-
-
- label18
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 26
-
-
- SV3_POS
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 27
-
-
- SV2_POS
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 28
-
-
- SV1_POS
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 29
-
-
- HS3_REV
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 30
-
-
- HS2_REV
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 31
-
-
- HS1_REV
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 32
-
-
- label17
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 33
-
-
- HS4
-
-
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabHeli
-
-
- 34
-
-
- HS3
-
-
- ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabHeli
-
-
- 35
-
-
- Gservoloc
-
-
- AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabHeli
-
-
- 36
-
-
- 4, 22
-
-
- 666, 393
-
-
- 5
-
-
- AC2 Heli
-
-
- tabHeli
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- Tabs
-
-
- 6
-
-
- Fill
-
-
- 0, 0
-
-
- 674, 419
-
-
- 93
-
-
- Tabs
-
-
- System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- $this
-
-
- 0
-
-
- CHK_mixmode
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBoxElevons
-
-
- 0
-
-
- CHK_elevonch2rev
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBoxElevons
-
-
- 1
-
-
- CHK_elevonrev
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBoxElevons
-
-
- 2
-
-
- CHK_elevonch1rev
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBoxElevons
-
-
- 3
-
-
- 21, 349
-
-
- 409, 42
-
-
- 111
-
-
- Elevon Config
-
-
- groupBoxElevons
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabRadioIn
-
-
- 0
-
True
+
NoControl
+
13, 19
@@ -1896,6 +255,30 @@
3
+
+ 21, 349
+
+
+ 409, 42
+
+
+ 111
+
+
+ Elevon Config
+
+
+ groupBoxElevons
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabRadioIn
+
+
+ 0
+
True
@@ -2067,9 +450,6 @@
6
-
- 17, 17
-
446, 185
@@ -2217,6 +597,33 @@
13
+
+ 4, 22
+
+
+ 3, 3, 3, 3
+
+
+ 666, 393
+
+
+ 0
+
+
+ Radio Input
+
+
+ tabRadioIn
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Tabs
+
+
+ 0
+
True
@@ -3048,6 +1455,30 @@
28
+
+ 4, 22
+
+
+ 666, 393
+
+
+ 3
+
+
+ Modes
+
+
+ tabModes
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Tabs
+
+
+ 1
+
405, 25
@@ -3432,150 +1863,33 @@
13
-
- label31
+
+ 4, 22
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+ 3, 3, 3, 3
-
- groupBox4
+
+ 666, 393
-
- 0
-
-
- label32
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
+
1
-
- label33
+
+ Hardware
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+ tabHardware
-
- groupBox4
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
+ Tabs
+
+
2
-
- TXT_ampspervolt
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 3
-
-
- label34
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 4
-
-
- TXT_divider
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 5
-
-
- label35
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 6
-
-
- TXT_voltage
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 7
-
-
- TXT_inputvoltage
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 8
-
-
- TXT_measuredvoltage
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 9
-
-
- 31, 177
-
-
- 238, 131
-
-
- 41
-
-
- Calibration
-
-
- groupBox4
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabBattery
-
-
- 0
-
True
@@ -3861,6 +2175,30 @@
9
+
+ 31, 177
+
+
+ 238, 131
+
+
+ 41
+
+
+ Calibration
+
+
+ groupBox4
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 0
+
NoControl
@@ -4092,6 +2430,117 @@ Then subtract 0.3v from that value and enter it in field #1 at left.
8
+
+ 4, 22
+
+
+ 2, 2, 2, 2
+
+
+ 666, 393
+
+
+ 6
+
+
+ Battery
+
+
+ tabBattery
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Tabs
+
+
+ 3
+
+
+ True
+
+
+ NoControl
+
+
+ 228, 170
+
+
+ 212, 13
+
+
+ 11
+
+
+ Level your plane to set default accel offsets
+
+
+ label48
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabArduplane
+
+
+ 0
+
+
+ NoControl
+
+
+ 285, 199
+
+
+ 75, 23
+
+
+ 10
+
+
+ Level
+
+
+ BUT_levelplane
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
+
+
+ tabArduplane
+
+
+ 1
+
+
+ 4, 22
+
+
+ 3, 3, 3, 3
+
+
+ 666, 393
+
+
+ 7
+
+
+ ArduPlane
+
+
+ tabArduplane
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Tabs
+
+
+ 4
+
True
@@ -4264,53 +2713,29 @@ will work with hexa's etc
5
-
- H1_ENABLE
+
+ 4, 22
-
- System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+ 666, 393
-
- groupBox5
+
+ 2
-
- 0
+
+ ArduCopter2
-
- CCPM
+
+ tabArducopter
-
- System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
- groupBox5
+
+ Tabs
-
- 1
-
-
- 253, 6
-
-
- 120, 43
-
-
- 137
-
-
- Swash Type
-
-
- groupBox5
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 0
+
+ 5
True
@@ -4369,6 +2794,30 @@ will work with hexa's etc
1
+
+ 253, 6
+
+
+ 120, 43
+
+
+ 137
+
+
+ Swash Type
+
+
+ groupBox5
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 0
+
NoControl
@@ -4423,78 +2872,6 @@ will work with hexa's etc
2
-
- 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
-
-
- GYR_ENABLE
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox3
-
-
- 2
-
-
- GYR_GAIN
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox3
-
-
- 3
-
-
- 433, 309
-
-
- 101, 63
-
-
- 135
-
-
- Gyro
-
-
- groupBox3
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 3
-
True
@@ -4606,6 +2983,30 @@ will work with hexa's etc
3
+
+ 433, 309
+
+
+ 101, 63
+
+
+ 135
+
+
+ Gyro
+
+
+ groupBox3
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 3
+
True
@@ -4696,75 +3097,6 @@ will work with hexa's etc
6
-
- label24
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox2
-
-
- 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
-
-
- 433, 181
-
-
- 169, 78
-
-
- 130
-
-
- groupBox2
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 7
-
True
@@ -4879,98 +3211,26 @@ will work with hexa's etc
3
-
- label41
+
+ 433, 181
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+ 169, 78
-
- groupBox1
+
+ 130
-
- 0
+
+ groupBox2
-
- label21
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 1
-
-
- COL_MIN
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 2
-
-
- COL_MID
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 3
-
-
- COL_MAX
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 4
-
-
- BUT_0collective
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- groupBox1
-
-
- 5
-
-
- 293, 90
-
-
- 80, 209
-
-
- 129
-
-
- groupBox1
-
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
tabHeli
-
- 8
+
+ 7
True
@@ -5143,6 +3403,27 @@ will work with hexa's etc
5
+
+ 293, 90
+
+
+ 80, 209
+
+
+ 129
+
+
+ groupBox1
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 8
+
535, 279
@@ -5887,6 +4168,69 @@ will work with hexa's etc
36
+
+ 4, 22
+
+
+ 666, 393
+
+
+ 5
+
+
+ AC2 Heli
+
+
+ tabHeli
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ Tabs
+
+
+ 6
+
+
+ Fill
+
+
+ 0, 0
+
+
+ 674, 419
+
+
+ 93
+
+
+ Tabs
+
+
+ System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 0
+
+
+ NoControl
+
+
+ 214, 161
+
+
+ 195, 23
+
+
+ 0
+
+
+ Reset APM Hardware to Default
+
BUT_reset
@@ -5917,33 +4261,6 @@ will work with hexa's etc
System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
- NoControl
-
-
- 214, 161
-
-
- 195, 23
-
-
- 0
-
-
- Reset APM Hardware to Default
-
-
- BUT_reset
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null
-
-
- tabReset
-
-
- 0
-
True
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb
index bbb6da8b86..11248adcb8 100644
Binary files a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb and b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb differ
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/Rascal/Rascal.xml b/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/Rascal/Rascal.xml
index 2e2813a25b..bf4321ee12 100644
--- a/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/Rascal/Rascal.xml
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/Rascal/Rascal.xml
@@ -86,7 +86,7 @@
68.9
0
- -3
+ -13.1
8.0
5.0
diff --git a/Tools/ArdupilotMegaPlanner/wix/Program.cs b/Tools/ArdupilotMegaPlanner/wix/Program.cs
index c08e4452db..e66a3cda2a 100644
--- a/Tools/ArdupilotMegaPlanner/wix/Program.cs
+++ b/Tools/ArdupilotMegaPlanner/wix/Program.cs
@@ -4,11 +4,55 @@ using System.Text;
using System.IO;
using System.Windows.Forms;
using System.Diagnostics;
+using System.Runtime.InteropServices;
namespace wix
{
class Program
{
+ ///
+ /// The operation completed successfully.
+ ///
+ public const int ERROR_SUCCESS = 0;
+ ///
+ /// Incorrect function.
+ ///
+ public const int ERROR_INVALID_FUNCTION = 1;
+ ///
+ /// The system cannot find the file specified.
+ ///
+ public const int ERROR_FILE_NOT_FOUND = 2;
+ ///
+ /// The system cannot find the path specified.
+ ///
+ public const int ERROR_PATH_NOT_FOUND = 3;
+ ///
+ /// The system cannot open the file.
+ ///
+ public const int ERROR_TOO_MANY_OPEN_FILES = 4;
+ ///
+ /// Access is denied.
+ ///
+ public const int ERROR_ACCESS_DENIED = 5;
+
+ const Int32 DRIVER_PACKAGE_REPAIR = 0x00000001;
+ const Int32 DRIVER_PACKAGE_SILENT = 0x00000002;
+ const Int32 DRIVER_PACKAGE_FORCE = 0x00000004;
+ const Int32 DRIVER_PACKAGE_ONLY_IF_DEVICE_PRESENT = 0x00000008;
+ const Int32 DRIVER_PACKAGE_LEGACY_MODE = 0x00000010;
+ const Int32 DRIVER_PACKAGE_DELETE_FILES = 0x00000020;
+
+ [DllImport("DIFXApi.dll", CharSet = CharSet.Unicode)]
+ public static extern Int32 DriverPackagePreinstall(string DriverPackageInfPath, Int32 Flags);
+
+ static void driverinstall()
+ {
+ int result = DriverPackagePreinstall(@"..\Driver\Arduino MEGA 2560.inf", 0);
+ if (result != 0)
+ MessageBox.Show("Driver installation failed. " + result);
+
+ }
+
static int no = 0;
static StreamWriter sw;
@@ -25,6 +69,12 @@ namespace wix
return;
}
+ if (args[0] == "driver")
+ {
+ driverinstall();
+ return;
+ }
+
string path = args[0];
string file = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar+ "installer.wxs";
@@ -190,12 +240,13 @@ data = @"
string[] dirs = Directory.GetDirectories(path);
if (level != 0)
- sw.WriteLine("");
+ sw.WriteLine("");
string[] files = Directory.GetFiles(path);
- sw.WriteLine("");
+ no++;
+ sw.WriteLine("");
components.Add("_comp"+no);
foreach (string filepath in files)
diff --git a/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.Designer.cs b/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.Designer.cs
new file mode 100644
index 0000000000..8e668211f7
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.Designer.cs
@@ -0,0 +1,63 @@
+//------------------------------------------------------------------------------
+//
+// This code was generated by a tool.
+// Runtime Version:4.0.30319.261
+//
+// Changes to this file may cause incorrect behavior and will be lost if
+// the code is regenerated.
+//
+//------------------------------------------------------------------------------
+
+namespace wix.Properties {
+ using System;
+
+
+ ///
+ /// A strongly-typed resource class, for looking up localized strings, etc.
+ ///
+ // This class was auto-generated by the StronglyTypedResourceBuilder
+ // class via a tool like ResGen or Visual Studio.
+ // To add or remove a member, edit your .ResX file then rerun ResGen
+ // with the /str option, or rebuild your VS project.
+ [global::System.CodeDom.Compiler.GeneratedCodeAttribute("System.Resources.Tools.StronglyTypedResourceBuilder", "4.0.0.0")]
+ [global::System.Diagnostics.DebuggerNonUserCodeAttribute()]
+ [global::System.Runtime.CompilerServices.CompilerGeneratedAttribute()]
+ internal class Resources {
+
+ private static global::System.Resources.ResourceManager resourceMan;
+
+ private static global::System.Globalization.CultureInfo resourceCulture;
+
+ [global::System.Diagnostics.CodeAnalysis.SuppressMessageAttribute("Microsoft.Performance", "CA1811:AvoidUncalledPrivateCode")]
+ internal Resources() {
+ }
+
+ ///
+ /// Returns the cached ResourceManager instance used by this class.
+ ///
+ [global::System.ComponentModel.EditorBrowsableAttribute(global::System.ComponentModel.EditorBrowsableState.Advanced)]
+ internal static global::System.Resources.ResourceManager ResourceManager {
+ get {
+ if (object.ReferenceEquals(resourceMan, null)) {
+ global::System.Resources.ResourceManager temp = new global::System.Resources.ResourceManager("wix.Properties.Resources", typeof(Resources).Assembly);
+ resourceMan = temp;
+ }
+ return resourceMan;
+ }
+ }
+
+ ///
+ /// Overrides the current thread's CurrentUICulture property for all
+ /// resource lookups using this strongly typed resource class.
+ ///
+ [global::System.ComponentModel.EditorBrowsableAttribute(global::System.ComponentModel.EditorBrowsableState.Advanced)]
+ internal static global::System.Globalization.CultureInfo Culture {
+ get {
+ return resourceCulture;
+ }
+ set {
+ resourceCulture = value;
+ }
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.resx b/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.resx
new file mode 100644
index 0000000000..4fdb1b6aff
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.resx
@@ -0,0 +1,101 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ text/microsoft-resx
+
+
+ 1.3
+
+
+ System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.3500.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.3500.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.Designer.cs b/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.Designer.cs
new file mode 100644
index 0000000000..50ea81e4e8
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.Designer.cs
@@ -0,0 +1,26 @@
+//------------------------------------------------------------------------------
+//
+// This code was generated by a tool.
+// Runtime Version:4.0.30319.261
+//
+// Changes to this file may cause incorrect behavior and will be lost if
+// the code is regenerated.
+//
+//------------------------------------------------------------------------------
+
+namespace wix.Properties {
+
+
+ [global::System.Runtime.CompilerServices.CompilerGeneratedAttribute()]
+ [global::System.CodeDom.Compiler.GeneratedCodeAttribute("Microsoft.VisualStudio.Editors.SettingsDesigner.SettingsSingleFileGenerator", "10.0.0.0")]
+ internal sealed partial class Settings : global::System.Configuration.ApplicationSettingsBase {
+
+ private static Settings defaultInstance = ((Settings)(global::System.Configuration.ApplicationSettingsBase.Synchronized(new Settings())));
+
+ public static Settings Default {
+ get {
+ return defaultInstance;
+ }
+ }
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.settings b/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.settings
new file mode 100644
index 0000000000..049245f401
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.settings
@@ -0,0 +1,6 @@
+
+
+
+
+
+
diff --git a/Tools/ArdupilotMegaPlanner/wix/Properties/app.manifest b/Tools/ArdupilotMegaPlanner/wix/Properties/app.manifest
new file mode 100644
index 0000000000..8948c3006c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Properties/app.manifest
@@ -0,0 +1,47 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/wix/wix.csproj b/Tools/ArdupilotMegaPlanner/wix/wix.csproj
index e20f105243..42fbee7ca3 100644
--- a/Tools/ArdupilotMegaPlanner/wix/wix.csproj
+++ b/Tools/ArdupilotMegaPlanner/wix/wix.csproj
@@ -10,7 +10,7 @@
Properties
wix
wix
- v2.0
+ v3.5
512
@@ -49,6 +49,16 @@
prompt
4
+
+
+ LocalIntranet
+
+
+ false
+
+
+ Properties\app.manifest
+
@@ -58,9 +68,24 @@
+
+ True
+ True
+ Resources.resx
+
+
+ True
+ True
+ Settings.settings
+
+
+
+ SettingsSingleFileGenerator
+ Settings.Designer.cs
+
@@ -79,6 +104,12 @@
true
+
+
+ ResXFileCodeGenerator
+ Resources.Designer.cs
+
+