Mission Planner 1.2.1

add enable/disable to mavlinkcheckbox
modify my button to curved
add delay to progress reporter dialog. to ensure correct parent
Fix Mount screen for AP
Fix Hardware screen Text
display roi difrently
modify HIL/Quad Hil
update dataflashlog format (thanks randy)
update mavcmd format for roi
This commit is contained in:
Michael Oborne 2012-07-30 07:23:42 +08:00
parent cb61c3be96
commit 8001515b7e
31 changed files with 2277 additions and 1619 deletions

View File

@ -177,14 +177,14 @@ namespace ArdupilotMega.Arduino
// all apm 1-1.4 use a ftdi on the imu board.
obj2.Properties.ForEach(x =>
/* obj2.Properties.ForEach(x =>
{
try
{
log.Info(((PropertyData)x).Name.ToString() + " = " + ((PropertyData)x).Value.ToString());
}
catch { }
});
});*/
// check vid and pid
if (obj2.Properties["PNPDeviceID"].Value.ToString().Contains(@"USB\VID_2341&PID_0010"))

View File

@ -70,10 +70,10 @@
<UseVSHostingProcess>true</UseVSHostingProcess>
<FileAlignment>512</FileAlignment>
</PropertyGroup>
<PropertyGroup Condition="'$(Mavlink10)'=='true'">
<DefineConstants>$(DefineConstants);MAVLINK10</DefineConstants>
<AssemblyName>ArdupilotMegaPlanner10</AssemblyName>
<OutputPath>bin\Release10\</OutputPath>
<PropertyGroup Condition="'$(Mavlink10)'=='false'">
<DefineConstants>TRACE;DEBUG</DefineConstants>
<AssemblyName>ArdupilotMegaPlanner</AssemblyName>
<OutputPath>bin\Release09\</OutputPath>
</PropertyGroup>
<PropertyGroup>
<StartupObject>ArdupilotMega.Program</StartupObject>
@ -182,6 +182,10 @@
<Reference Include="OpenTK.GLControl, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
</Reference>
<Reference Include="Sharp3D.Math, Version=1.1.3.0, Culture=neutral, PublicKeyToken=529e2e82fcc0ba71">
<SpecificVersion>False</SpecificVersion>
<HintPath>Lib\Sharp3D.Math.dll</HintPath>
</Reference>
<Reference Include="SharpKml, Version=1.1.0.0, Culture=neutral, PublicKeyToken=e608cd7d975805ad, processorArchitecture=MSIL">
<SpecificVersion>False</SpecificVersion>
</Reference>
@ -279,6 +283,9 @@
<Compile Include="GCSViews\ConfigurationView\ConfigMount.designer.cs">
<DependentUpon>ConfigMount.cs</DependentUpon>
</Compile>
<Compile Include="HIL\FlashQuad.cs" />
<Compile Include="HIL\Matrix3.cs" />
<Compile Include="HIL\Vector3.cs" />
<Compile Include="Presenter\ConfigCameraStabPresenter.cs" />
<Compile Include="Controls\HSI.cs">
<SubType>UserControl</SubType>

View File

@ -1,4 +1,63 @@
* APM Planner 1.1.95
* Mission Planner 1.2
Enable Mount config screen
Add Quick View (double click to change)
fix mono updater issue
RFD900 transmit values Mod
new mavlink controls (wip)
* APM Planner 1.1.99
Convert to IActivate, IDeactivate scheme, thanks andrew
add support for rfcomm* interfaces on linux
fix guage off screen draw mono issue.
remove use of BackStageViewContentPanel
andrews spacer changes - not using dues to screen space issue
change configpanel constructor to load xml directly
remove IMavlink Interface
fix hsi off screen draw issue on mono
modify hud to use sprite fonts, instead of drawing via GDI+
modify progress reporter to use a 10hz timer to update screen, using invoke/begininvoke fails on mono at 50hz (over 100ms per call).
fix targetalt and target airspeed jumping issue.
lots of cleanup on tab switching, ie stoping timers/other
3dr radio status led update
update ardurover car icon
speedup georef image screen. tested on over 1000 images.
* APM Planner 1.1.98
Modify BackStage View - will change again soon
modify target alt calc
change order on param lists
remove old firmware selection dialog
add hil mod flag to hil connect
implement main switcher - will change again soon
change some invokes to async, to prevent other threads slowing.
fix mavlink log graphing error
modify help text
general mono for mac fixs - still combating https://bugzilla.xamarin.com/show_bug.cgi?id=3124
* APM Planner 1.1.97
add toy Mode
fix some mono issues
fix opengl hud issue
change config font size
modify mylabel for mono
modify default telem rates
add extra sonar option
remove 0 home alt check
fix terminal hang issue
remove application idle call, causes 100% cpu on mono
update gimbal icons
modify graph line thinkness
* APM Planner 1.1.96
Fix camera stab reverse boxs
add better param data duplicate handling
add rfd900a
tweak terminal settings
* APM Planner 1.1.95
fix config panel value change detection
add loiter_ to AC config screen
Add praram name to Friendly param, and exception ignoring.

View File

@ -836,6 +836,7 @@ namespace ArdupilotMega
ArdupilotMega.Controls.MyButton buttonCancel = new ArdupilotMega.Controls.MyButton();
form.TopMost = true;
form.TopLevel = true;
form.Text = title;
label.Text = promptText;

View File

@ -21,6 +21,8 @@ namespace ArdupilotMega.Controls
[System.ComponentModel.Browsable(true)]
public Hashtable param { get; set; }
Control _control;
public MavlinkCheckBox()
{
OnValue = 1;
@ -29,7 +31,7 @@ namespace ArdupilotMega.Controls
this.Enabled = false;
}
public void setup(float OnValue, float OffValue, string paramname, Hashtable paramlist)
public void setup(float OnValue, float OffValue, string paramname, Hashtable paramlist, Control enabledisable = null)
{
base.CheckedChanged -= MavlinkCheckBox_CheckedChanged;
@ -37,6 +39,7 @@ namespace ArdupilotMega.Controls
this.OffValue = OffValue;
this.ParamName = paramname;
this.param = paramlist;
this._control = enabledisable;
if (paramlist.ContainsKey(paramname))
{
@ -45,24 +48,38 @@ namespace ArdupilotMega.Controls
if ((float)paramlist[paramname] == OnValue)
{
this.Checked = true;
enableControl(true);
}
else if ((float)paramlist[paramname] == OffValue)
{
this.Checked = false;
enableControl(false);
}
else
{
this.CheckState = System.Windows.Forms.CheckState.Indeterminate;
enableControl(false);
}
}
else
{
this.Enabled = false;
}
base.CheckedChanged += new EventHandler(MavlinkCheckBox_CheckedChanged);
}
void enableControl(bool enable)
{
if (_control != null)
_control.Enabled = enable;
}
void MavlinkCheckBox_CheckedChanged(object sender, EventArgs e)
{
if (this.Checked)
{
enableControl(true);
if (!MainV2.comPort.setParam(ParamName, OnValue))
{
CustomMessageBox.Show("Set "+ParamName + " Failed!");
@ -70,6 +87,7 @@ namespace ArdupilotMega.Controls
}
else
{
enableControl(false);
if (!MainV2.comPort.setParam(ParamName, OffValue))
{
CustomMessageBox.Show("Set " + ParamName + " Failed!");

View File

@ -41,43 +41,46 @@ namespace ArdupilotMega.Controls
{
Graphics gr = pevent.Graphics;
// gr.SmoothingMode = SmoothingMode.AntiAlias;
gr.Clear(this.BackColor);
gr.SmoothingMode = SmoothingMode.AntiAlias;
Rectangle outside = new Rectangle(0, 0, this.Width, this.Height);
LinearGradientBrush linear = new LinearGradientBrush(outside, BGGradTop, BGGradBot, LinearGradientMode.Vertical);
Pen mypen = new Pen(Outline, 2);
/*
gr.FillRectangle(new SolidBrush(Color.FromArgb(0x26, 0x27, 0x28)), outside);
Pen mypen = new Pen(Outline, 1);
// gr.FillRectangle(new SolidBrush(Color.FromArgb(0x26, 0x27, 0x28)), outside);
GraphicsPath outline = new GraphicsPath();
float wid = this.Height / 5f;
float widright = wid + 1;
float wid = this.Height / 3f;
int width = this.Width - 1;
int height = this.Height - 1;
// tl
outline.AddArc(0, 0, wid, wid, 180, 90);
// top line
outline.AddLine(wid, 0, this.Width - widright, 0);
outline.AddLine(wid, 0, width - wid, 0);
// tr
outline.AddArc(this.Width - widright, 0, wid, wid, 270, 90);
outline.AddArc(width - wid, 0, wid, wid, 270, 90);
// br
outline.AddArc(this.Width - widright, this.Height - widright, wid, wid, 0, 90);
outline.AddArc(width - wid, height - wid, wid, wid, 0, 90);
// bottom line
outline.AddLine(wid, this.Height - 1, this.Width - widright, this.Height - 1);
outline.AddLine(wid, height, width - wid, height);
// bl
outline.AddArc(0, this.Height - widright, wid, wid, 90, 90);
outline.AddArc(0, height - wid, wid, wid, 90, 90);
gr.FillPath(linear, outline);
gr.DrawPath(mypen, outline);
// gr.DrawPath(mypen, outline);
*/
gr.FillRectangle(linear, outside);
gr.DrawRectangle(mypen, outside);
// gr.FillRectangle(linear, outside);
// gr.DrawRectangle(mypen, outside);
SolidBrush mybrush = new SolidBrush(TextColor);
@ -86,20 +89,20 @@ namespace ArdupilotMega.Controls
{
SolidBrush brush = new SolidBrush(Color.FromArgb(73, 0x2b, 0x3a, 0x03));
gr.FillRectangle(brush, 0, 0, this.Width, this.Height);
gr.FillPath(brush, outline);
}
if (mousedown)
{
SolidBrush brush = new SolidBrush(Color.FromArgb(73, 0x2b, 0x3a, 0x03));
gr.FillRectangle(brush, 0, 0, this.Width, this.Height);
gr.FillPath(brush, outline);
}
if (!this.Enabled)
{
SolidBrush brush = new SolidBrush(Color.FromArgb(150, 0x2b, 0x3a, 0x03));
gr.FillRectangle(brush, 0, 0, this.Width, this.Height);
gr.FillPath(brush, outline);
}

View File

@ -53,6 +53,13 @@ namespace ArdupilotMega.Controls
while (this.IsHandleCreated == false)
System.Threading.Thread.Sleep(1);
this.Invoke((MethodInvoker)delegate
{
// if this windows isnt the current active windows, popups inherit the wrong parent.
this.Focus();
Application.DoEvents();
});
try
{
if (this.DoWork != null) this.DoWork(this, doWorkArgs);
@ -215,15 +222,22 @@ namespace ArdupilotMega.Controls
/// <param name="e"></param>
private void timer1_Tick(object sender, EventArgs e)
{
// this value is being currupted - not thread safe
int pgv = _progress;
lblProgressMessage.Text = _status;
if (_progress == -1)
if (pgv == -1)
{
this.progressBar1.Style = ProgressBarStyle.Marquee;
}
else
{
this.progressBar1.Style = ProgressBarStyle.Continuous;
this.progressBar1.Value = _progress;
try
{
this.progressBar1.Value = pgv;
}
catch { } // clean fail. and ignore, chances are we will hit this again in the next 100 ms
}
}

View File

@ -78,7 +78,7 @@ namespace ArdupilotMega
public float mz { get; set; }
public float magfield { get { return (float)Math.Sqrt(Math.Pow(mx, 2) + Math.Pow(my, 2) + Math.Pow(mz, 2)); } }
public float accelsq { get { return (float)Math.Sqrt(Math.Pow(ax, 2) + Math.Pow(ay, 2) + Math.Pow(az, 2)) / 980.665f; } }
public float accelsq { get { return (float)Math.Sqrt(Math.Pow(ax, 2) + Math.Pow(ay, 2) + Math.Pow(az, 2)) / 1000.0f /*980.665f*/; } }
// calced turn rate
public float turnrate { get { if (groundspeed <= 1) return 0; return (roll * 9.8f) / groundspeed; } }
@ -324,6 +324,7 @@ namespace ArdupilotMega
// reference
public DateTime datetime { get; set; }
private object locker = new object();
public CurrentState()
{
@ -356,195 +357,199 @@ namespace ArdupilotMega
*/
public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs, bool updatenow, MAVLink mavinterface)
{
if (DateTime.Now > lastupdate.AddMilliseconds(19) || updatenow) // 50 hz
lock (locker)
{
lastupdate = DateTime.Now;
if (DateTime.Now.Second != lastwindcalc.Second)
if (DateTime.Now > lastupdate.AddMilliseconds(19) || updatenow) // 50 hz
{
lastwindcalc = DateTime.Now;
dowindcalc();
}
lastupdate = DateTime.Now;
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text
{
string logdata = DateTime.Now + " " + Encoding.ASCII.GetString(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT], 6, mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT].Length - 6);
int ind = logdata.IndexOf('\0');
if (ind != -1)
logdata = logdata.Substring(0, ind);
try
if (DateTime.Now.Second != lastwindcalc.Second)
{
while (messages.Count > 5)
{
messages.RemoveAt(0);
}
messages.Add(logdata + "\n");
lastwindcalc = DateTime.Now;
dowindcalc();
}
catch { }
mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] = null;
}
byte[] bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED];
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text
{
if (bytearray != null) // hil mavlink 0.9
{
var hil = bytearray.ByteArrayToStructure<MAVLink.mavlink_rc_channels_scaled_t>(6);
string logdata = DateTime.Now + " " + Encoding.ASCII.GetString(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT], 6, mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT].Length - 6);
hilch1 = hil.chan1_scaled;
hilch2 = hil.chan2_scaled;
hilch3 = hil.chan3_scaled;
hilch4 = hil.chan4_scaled;
hilch5 = hil.chan5_scaled;
hilch6 = hil.chan6_scaled;
hilch7 = hil.chan7_scaled;
hilch8 = hil.chan8_scaled;
int ind = logdata.IndexOf('\0');
if (ind != -1)
logdata = logdata.Substring(0, ind);
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] = null;
}
try
{
while (messages.Count > 5)
{
messages.RemoveAt(0);
}
messages.Add(logdata + "\n");
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HIL_CONTROLS];
}
catch { }
mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] = null;
}
if (bytearray != null) // hil mavlink 0.9 and 1.0
{
var hil = bytearray.ByteArrayToStructure<MAVLink.mavlink_hil_controls_t>(6);
byte[] bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED];
hilch1 = (int)(hil.roll_ailerons * 10000);
hilch2 = (int)(hil.pitch_elevator * 10000);
hilch3 = (int)(hil.throttle * 10000);
hilch4 = (int)(hil.yaw_rudder * 10000);
if (bytearray != null) // hil mavlink 0.9
{
var hil = bytearray.ByteArrayToStructure<MAVLink.mavlink_rc_channels_scaled_t>(6);
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_HIL_CONTROLS] = null;
}
hilch1 = hil.chan1_scaled;
hilch2 = hil.chan2_scaled;
hilch3 = hil.chan3_scaled;
hilch4 = hil.chan4_scaled;
hilch5 = hil.chan5_scaled;
hilch6 = hil.chan6_scaled;
hilch7 = hil.chan7_scaled;
hilch8 = hil.chan8_scaled;
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HWSTATUS];
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] = null;
}
if (bytearray != null)
{
var hwstatus = bytearray.ByteArrayToStructure<MAVLink.mavlink_hwstatus_t>(6);
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HIL_CONTROLS];
hwvoltage = hwstatus.Vcc;
i2cerrors = hwstatus.I2Cerr;
if (bytearray != null) // hil mavlink 0.9 and 1.0
{
var hil = bytearray.ByteArrayToStructure<MAVLink.mavlink_hil_controls_t>(6);
hilch1 = (int)(hil.roll_ailerons * 10000);
hilch2 = (int)(hil.pitch_elevator * 10000);
hilch3 = (int)(hil.throttle * 10000);
hilch4 = (int)(hil.yaw_rudder * 10000);
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_HIL_CONTROLS] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HWSTATUS];
if (bytearray != null)
{
var hwstatus = bytearray.ByteArrayToStructure<MAVLink.mavlink_hwstatus_t>(6);
hwvoltage = hwstatus.Vcc;
i2cerrors = hwstatus.I2Cerr;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_HWSTATUS] = null;
}
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_HWSTATUS] = null;
}
#if MAVLINK10
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HEARTBEAT];
if (bytearray != null)
{
var hb = bytearray.ByteArrayToStructure<MAVLink.mavlink_heartbeat_t>(6);
armed = (hb.base_mode & (byte)MAVLink.MAV_MODE_FLAG.SAFETY_ARMED) == (byte)MAVLink.MAV_MODE_FLAG.SAFETY_ARMED ? 4 : 3;
string oldmode = mode;
mode = "Unknown";
if ((hb.base_mode & (byte)MAVLink.MAV_MODE_FLAG.CUSTOM_MODE_ENABLED) != 0)
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HEARTBEAT];
if (bytearray != null)
{
if (hb.type == (byte)MAVLink.MAV_TYPE.FIXED_WING)
var hb = bytearray.ByteArrayToStructure<MAVLink.mavlink_heartbeat_t>(6);
armed = (hb.base_mode & (byte)MAVLink.MAV_MODE_FLAG.SAFETY_ARMED) == (byte)MAVLink.MAV_MODE_FLAG.SAFETY_ARMED ? 4 : 3;
string oldmode = mode;
mode = "Unknown";
if ((hb.base_mode & (byte)MAVLink.MAV_MODE_FLAG.CUSTOM_MODE_ENABLED) != 0)
{
switch (hb.custom_mode)
if (hb.type == (byte)MAVLink.MAV_TYPE.FIXED_WING)
{
case (byte)(Common.apmmodes.MANUAL):
mode = "Manual";
break;
case (byte)(Common.apmmodes.GUIDED):
mode = "Guided";
break;
case (byte)(Common.apmmodes.STABILIZE):
mode = "Stabilize";
break;
case (byte)(Common.apmmodes.FLY_BY_WIRE_A):
mode = "FBW A";
break;
case (byte)(Common.apmmodes.FLY_BY_WIRE_B):
mode = "FBW B";
break;
case (byte)(Common.apmmodes.AUTO):
mode = "Auto";
break;
case (byte)(Common.apmmodes.RTL):
mode = "RTL";
break;
case (byte)(Common.apmmodes.LOITER):
mode = "Loiter";
break;
case (byte)(Common.apmmodes.CIRCLE):
mode = "Circle";
break;
case 16:
mode = "Initialising";
break;
default:
mode = "Unknown";
break;
switch (hb.custom_mode)
{
case (byte)(Common.apmmodes.MANUAL):
mode = "Manual";
break;
case (byte)(Common.apmmodes.GUIDED):
mode = "Guided";
break;
case (byte)(Common.apmmodes.STABILIZE):
mode = "Stabilize";
break;
case (byte)(Common.apmmodes.FLY_BY_WIRE_A):
mode = "FBW A";
break;
case (byte)(Common.apmmodes.FLY_BY_WIRE_B):
mode = "FBW B";
break;
case (byte)(Common.apmmodes.AUTO):
mode = "Auto";
break;
case (byte)(Common.apmmodes.RTL):
mode = "RTL";
break;
case (byte)(Common.apmmodes.LOITER):
mode = "Loiter";
break;
case (byte)(Common.apmmodes.CIRCLE):
mode = "Circle";
break;
case 16:
mode = "Initialising";
break;
default:
mode = "Unknown";
break;
}
}
else if (hb.type == (byte)MAVLink.MAV_TYPE.QUADROTOR)
{
switch (hb.custom_mode)
{
case (byte)(Common.ac2modes.STABILIZE):
mode = "Stabilize";
break;
case (byte)(Common.ac2modes.ACRO):
mode = "Acro";
break;
case (byte)(Common.ac2modes.ALT_HOLD):
mode = "Alt Hold";
break;
case (byte)(Common.ac2modes.AUTO):
mode = "Auto";
break;
case (byte)(Common.ac2modes.GUIDED):
mode = "Guided";
break;
case (byte)(Common.ac2modes.LOITER):
mode = "Loiter";
break;
case (byte)(Common.ac2modes.RTL):
mode = "RTL";
break;
case (byte)(Common.ac2modes.CIRCLE):
mode = "Circle";
break;
case (byte)(Common.ac2modes.LAND):
mode = "Land";
break;
default:
mode = "Unknown";
break;
}
}
}
else if (hb.type == (byte)MAVLink.MAV_TYPE.QUADROTOR)
if (oldmode != mode && MainV2.speechEnable && MainV2.getConfig("speechmodeenabled") == "True")
{
switch (hb.custom_mode)
{
case (byte)(Common.ac2modes.STABILIZE):
mode = "Stabilize";
break;
case (byte)(Common.ac2modes.ACRO):
mode = "Acro";
break;
case (byte)(Common.ac2modes.ALT_HOLD):
mode = "Alt Hold";
break;
case (byte)(Common.ac2modes.AUTO):
mode = "Auto";
break;
case (byte)(Common.ac2modes.GUIDED):
mode = "Guided";
break;
case (byte)(Common.ac2modes.LOITER):
mode = "Loiter";
break;
case (byte)(Common.ac2modes.RTL):
mode = "RTL";
break;
case (byte)(Common.ac2modes.CIRCLE):
mode = "Circle";
break;
case (byte)(Common.ac2modes.LAND):
mode = "Land";
break;
default:
mode = "Unknown";
break;
}
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechmode")));
}
}
if (oldmode != mode && MainV2.speechEnable && MainV2.getConfig("speechmodeenabled") == "True")
bytearray = mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS];
if (bytearray != null)
{
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechmode")));
var sysstatus = bytearray.ByteArrayToStructure<MAVLink.mavlink_sys_status_t>(6);
battery_voltage = sysstatus.voltage_battery;
battery_remaining = sysstatus.battery_remaining;
current = sysstatus.current_battery;
packetdropremote = sysstatus.drop_rate_comm;
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] = null;
}
}
bytearray = mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS];
if (bytearray != null)
{
var sysstatus = bytearray.ByteArrayToStructure<MAVLink.mavlink_sys_status_t>(6);
battery_voltage = sysstatus.voltage_battery;
battery_remaining = sysstatus.battery_remaining;
current = sysstatus.current_battery;
packetdropremote = sysstatus.drop_rate_comm;
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] = null;
}
#else
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SYS_STATUS];
@ -665,73 +670,73 @@ namespace ArdupilotMega
}
#endif
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_PRESSURE];
if (bytearray != null)
{
var pres = bytearray.ByteArrayToStructure<MAVLink.mavlink_scaled_pressure_t>(6);
press_abs = pres.press_abs;
press_temp = pres.temperature;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_PRESSURE];
if (bytearray != null)
{
var pres = bytearray.ByteArrayToStructure<MAVLink.mavlink_scaled_pressure_t>(6);
press_abs = pres.press_abs;
press_temp = pres.temperature;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SENSOR_OFFSETS];
if (bytearray != null)
{
var sensofs = bytearray.ByteArrayToStructure<MAVLink.mavlink_sensor_offsets_t>(6);
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SENSOR_OFFSETS];
if (bytearray != null)
{
var sensofs = bytearray.ByteArrayToStructure<MAVLink.mavlink_sensor_offsets_t>(6);
mag_ofs_x = sensofs.mag_ofs_x;
mag_ofs_y = sensofs.mag_ofs_y;
mag_ofs_z = sensofs.mag_ofs_z;
mag_declination = sensofs.mag_declination;
mag_ofs_x = sensofs.mag_ofs_x;
mag_ofs_y = sensofs.mag_ofs_y;
mag_ofs_z = sensofs.mag_ofs_z;
mag_declination = sensofs.mag_declination;
raw_press = sensofs.raw_press;
raw_temp = sensofs.raw_temp;
raw_press = sensofs.raw_press;
raw_temp = sensofs.raw_temp;
gyro_cal_x = sensofs.gyro_cal_x;
gyro_cal_y = sensofs.gyro_cal_y;
gyro_cal_z = sensofs.gyro_cal_z;
gyro_cal_x = sensofs.gyro_cal_x;
gyro_cal_y = sensofs.gyro_cal_y;
gyro_cal_z = sensofs.gyro_cal_z;
accel_cal_x = sensofs.accel_cal_x;
accel_cal_y = sensofs.accel_cal_y;
accel_cal_z = sensofs.accel_cal_z;
accel_cal_x = sensofs.accel_cal_x;
accel_cal_y = sensofs.accel_cal_y;
accel_cal_z = sensofs.accel_cal_z;
}
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE];
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE];
if (bytearray != null)
{
var att = bytearray.ByteArrayToStructure<MAVLink.mavlink_attitude_t>(6);
if (bytearray != null)
{
var att = bytearray.ByteArrayToStructure<MAVLink.mavlink_attitude_t>(6);
roll = att.roll * rad2deg;
pitch = att.pitch * rad2deg;
yaw = att.yaw * rad2deg;
roll = att.roll * rad2deg;
pitch = att.pitch * rad2deg;
yaw = att.yaw * rad2deg;
// Console.WriteLine(roll + " " + pitch + " " + yaw);
// Console.WriteLine(roll + " " + pitch + " " + yaw);
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] = null;
}
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] = null;
}
#if MAVLINK10
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW_INT];
if (bytearray != null)
{
var gps = bytearray.ByteArrayToStructure<MAVLink.mavlink_gps_raw_int_t>(6);
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW_INT];
if (bytearray != null)
{
var gps = bytearray.ByteArrayToStructure<MAVLink.mavlink_gps_raw_int_t>(6);
lat = gps.lat * 1.0e-7f;
lng = gps.lon * 1.0e-7f;
// alt = gps.alt; // using vfr as includes baro calc
lat = gps.lat * 1.0e-7f;
lng = gps.lon * 1.0e-7f;
// alt = gps.alt; // using vfr as includes baro calc
gpsstatus = gps.fix_type;
// Console.WriteLine("gpsfix {0}",gpsstatus);
gpsstatus = gps.fix_type;
// Console.WriteLine("gpsfix {0}",gpsstatus);
gpshdop = gps.eph;
gpshdop = gps.eph;
satcount = gps.satellites_visible;
satcount = gps.satellites_visible;
groundspeed = gps.vel * 1.0e-2f;
groundcourse = gps.cog * 1.0e-2f;
groundspeed = gps.vel * 1.0e-2f;
groundcourse = gps.cog * 1.0e-2f;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] = null;
}
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] = null;
}
#else
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW];
@ -755,52 +760,52 @@ namespace ArdupilotMega
}
#endif
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS];
if (bytearray != null)
{
var gps = bytearray.ByteArrayToStructure<MAVLink.mavlink_gps_status_t>(6);
satcount = gps.satellites_visible;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RADIO];
if (bytearray != null)
{
var radio = bytearray.ByteArrayToStructure<MAVLink.mavlink_radio_t>(6);
rssi = radio.rssi;
remrssi = radio.remrssi;
txbuffer = radio.txbuf;
rxerrors = radio.rxerrors;
noise = radio.noise;
remnoise = radio.remnoise;
fixedp = radio.fixedp;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT];
if (bytearray != null)
{
var loc = bytearray.ByteArrayToStructure<MAVLink.mavlink_global_position_int_t>(6);
//alt = loc.alt / 1000.0f;
lat = loc.lat / 10000000.0f;
lng = loc.lon / 10000000.0f;
}
#if MAVLINK10
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MISSION_CURRENT];
if (bytearray != null)
{
var wpcur = bytearray.ByteArrayToStructure<MAVLink.mavlink_mission_current_t>(6);
int oldwp = (int)wpno;
wpno = wpcur.seq;
if (oldwp != wpno && MainV2.speechEnable && MainV2.getConfig("speechwaypointenabled") == "True")
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS];
if (bytearray != null)
{
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint")));
var gps = bytearray.ByteArrayToStructure<MAVLink.mavlink_gps_status_t>(6);
satcount = gps.satellites_visible;
}
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RADIO];
if (bytearray != null)
{
var radio = bytearray.ByteArrayToStructure<MAVLink.mavlink_radio_t>(6);
rssi = radio.rssi;
remrssi = radio.remrssi;
txbuffer = radio.txbuf;
rxerrors = radio.rxerrors;
noise = radio.noise;
remnoise = radio.remnoise;
fixedp = radio.fixedp;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT];
if (bytearray != null)
{
var loc = bytearray.ByteArrayToStructure<MAVLink.mavlink_global_position_int_t>(6);
//alt = loc.alt / 1000.0f;
lat = loc.lat / 10000000.0f;
lng = loc.lon / 10000000.0f;
}
#if MAVLINK10
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MISSION_CURRENT];
if (bytearray != null)
{
var wpcur = bytearray.ByteArrayToStructure<MAVLink.mavlink_mission_current_t>(6);
int oldwp = (int)wpno;
wpno = wpcur.seq;
if (oldwp != wpno && MainV2.speechEnable && MainV2.getConfig("speechwaypointenabled") == "True")
{
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint")));
}
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] = null;
}
#else
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION];
@ -832,145 +837,146 @@ namespace ArdupilotMega
#endif
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT];
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT];
if (bytearray != null)
{
var nav = bytearray.ByteArrayToStructure<MAVLink.mavlink_nav_controller_output_t>(6);
nav_roll = nav.nav_roll;
nav_pitch = nav.nav_pitch;
nav_bearing = nav.nav_bearing;
target_bearing = nav.target_bearing;
wp_dist = nav.wp_dist;
alt_error = nav.alt_error;
aspd_error = nav.aspd_error;
xtrack_error = nav.xtrack_error;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW];
if (bytearray != null)
{
var rcin = bytearray.ByteArrayToStructure<MAVLink.mavlink_rc_channels_raw_t>(6);
ch1in = rcin.chan1_raw;
ch2in = rcin.chan2_raw;
ch3in = rcin.chan3_raw;
ch4in = rcin.chan4_raw;
ch5in = rcin.chan5_raw;
ch6in = rcin.chan6_raw;
ch7in = rcin.chan7_raw;
ch8in = rcin.chan8_raw;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW];
if (bytearray != null)
{
var servoout = bytearray.ByteArrayToStructure<MAVLink.mavlink_servo_output_raw_t>(6);
ch1out = servoout.servo1_raw;
ch2out = servoout.servo2_raw;
ch3out = servoout.servo3_raw;
ch4out = servoout.servo4_raw;
ch5out = servoout.servo5_raw;
ch6out = servoout.servo6_raw;
ch7out = servoout.servo7_raw;
ch8out = servoout.servo8_raw;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU];
if (bytearray != null)
{
var imu = bytearray.ByteArrayToStructure<MAVLink.mavlink_raw_imu_t>(6);
gx = imu.xgyro;
gy = imu.ygyro;
gz = imu.zgyro;
ax = imu.xacc;
ay = imu.yacc;
az = imu.zacc;
mx = imu.xmag;
my = imu.ymag;
mz = imu.zmag;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU];
if (bytearray != null)
{
var imu = bytearray.ByteArrayToStructure<MAVLink.mavlink_scaled_imu_t>(6);
gx = imu.xgyro;
gy = imu.ygyro;
gz = imu.zgyro;
ax = imu.xacc;
ay = imu.yacc;
az = imu.zacc;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD];
if (bytearray != null)
{
var vfr = bytearray.ByteArrayToStructure<MAVLink.mavlink_vfr_hud_t>(6);
groundspeed = vfr.groundspeed;
airspeed = vfr.airspeed;
alt = vfr.alt; // this might include baro
//climbrate = vfr.climb;
if ((DateTime.Now - lastalt).TotalSeconds >= 0.2 && oldalt != alt)
if (bytearray != null)
{
climbrate = (alt - oldalt) / (float)(DateTime.Now - lastalt).TotalSeconds;
verticalspeed = (alt - oldalt) / (float)(DateTime.Now - lastalt).TotalSeconds;
if (float.IsInfinity(_verticalspeed))
_verticalspeed = 0;
lastalt = DateTime.Now;
oldalt = alt;
var nav = bytearray.ByteArrayToStructure<MAVLink.mavlink_nav_controller_output_t>(6);
nav_roll = nav.nav_roll;
nav_pitch = nav.nav_pitch;
nav_bearing = nav.nav_bearing;
target_bearing = nav.target_bearing;
wp_dist = nav.wp_dist;
alt_error = nav.alt_error;
aspd_error = nav.aspd_error;
xtrack_error = nav.xtrack_error;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] = null;
}
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] = null;
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW];
if (bytearray != null)
{
var rcin = bytearray.ByteArrayToStructure<MAVLink.mavlink_rc_channels_raw_t>(6);
ch1in = rcin.chan1_raw;
ch2in = rcin.chan2_raw;
ch3in = rcin.chan3_raw;
ch4in = rcin.chan4_raw;
ch5in = rcin.chan5_raw;
ch6in = rcin.chan6_raw;
ch7in = rcin.chan7_raw;
ch8in = rcin.chan8_raw;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW];
if (bytearray != null)
{
var servoout = bytearray.ByteArrayToStructure<MAVLink.mavlink_servo_output_raw_t>(6);
ch1out = servoout.servo1_raw;
ch2out = servoout.servo2_raw;
ch3out = servoout.servo3_raw;
ch4out = servoout.servo4_raw;
ch5out = servoout.servo5_raw;
ch6out = servoout.servo6_raw;
ch7out = servoout.servo7_raw;
ch8out = servoout.servo8_raw;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU];
if (bytearray != null)
{
var imu = bytearray.ByteArrayToStructure<MAVLink.mavlink_raw_imu_t>(6);
gx = imu.xgyro;
gy = imu.ygyro;
gz = imu.zgyro;
ax = imu.xacc;
ay = imu.yacc;
az = imu.zacc;
mx = imu.xmag;
my = imu.ymag;
mz = imu.zmag;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU];
if (bytearray != null)
{
var imu = bytearray.ByteArrayToStructure<MAVLink.mavlink_scaled_imu_t>(6);
gx = imu.xgyro;
gy = imu.ygyro;
gz = imu.zgyro;
ax = imu.xacc;
ay = imu.yacc;
az = imu.zacc;
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD];
if (bytearray != null)
{
var vfr = bytearray.ByteArrayToStructure<MAVLink.mavlink_vfr_hud_t>(6);
groundspeed = vfr.groundspeed;
airspeed = vfr.airspeed;
alt = vfr.alt; // this might include baro
//climbrate = vfr.climb;
if ((DateTime.Now - lastalt).TotalSeconds >= 0.2 && oldalt != alt)
{
climbrate = (alt - oldalt) / (float)(DateTime.Now - lastalt).TotalSeconds;
verticalspeed = (alt - oldalt) / (float)(DateTime.Now - lastalt).TotalSeconds;
if (float.IsInfinity(_verticalspeed))
_verticalspeed = 0;
lastalt = DateTime.Now;
oldalt = alt;
}
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] = null;
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO];
if (bytearray != null)
{
var mem = bytearray.ByteArrayToStructure<MAVLink.mavlink_meminfo_t>(6);
freemem = mem.freemem;
brklevel = mem.brkval;
}
}
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO];
if (bytearray != null)
//Console.WriteLine(DateTime.Now.Millisecond + " start ");
// update form
try
{
var mem = bytearray.ByteArrayToStructure<MAVLink.mavlink_meminfo_t>(6);
freemem = mem.freemem;
brklevel = mem.brkval;
if (bs != null)
{
//System.Diagnostics.Debug.WriteLine(DateTime.Now.Millisecond);
//Console.WriteLine(DateTime.Now.Millisecond);
bs.DataSource = this;
// Console.WriteLine(DateTime.Now.Millisecond + " 1 " + updatenow + " " + System.Threading.Thread.CurrentThread.Name);
bs.ResetBindings(false);
//Console.WriteLine(DateTime.Now.Millisecond + " done ");
}
}
catch { log.InfoFormat("CurrentState Binding error"); }
}
//Console.WriteLine(DateTime.Now.Millisecond + " start ");
// update form
try
{
if (bs != null)
{
//System.Diagnostics.Debug.WriteLine(DateTime.Now.Millisecond);
//Console.WriteLine(DateTime.Now.Millisecond);
bs.DataSource = this;
// Console.WriteLine(DateTime.Now.Millisecond + " 1 " + updatenow + " " + System.Threading.Thread.CurrentThread.Name);
bs.ResetBindings(false);
//Console.WriteLine(DateTime.Now.Millisecond + " done ");
}
}
catch { log.InfoFormat("CurrentState Binding error"); }
}
public object Clone()

View File

@ -30,24 +30,24 @@
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigAP_Limits));
this.LNK_wiki = new System.Windows.Forms.LinkLabel();
this.LIM_ENABLED = new System.Windows.Forms.CheckBox();
this.LIM_ENABLED = new ArdupilotMega.Controls.MavlinkCheckBox();
this.groupBox1 = new System.Windows.Forms.GroupBox();
this.textBox1 = new System.Windows.Forms.TextBox();
this.groupBox5 = new System.Windows.Forms.GroupBox();
this.LIM_GPSLCK_REQ = new System.Windows.Forms.CheckBox();
this.LIM_FNC_REQ = new System.Windows.Forms.CheckBox();
this.LIM_ALT_REQ = new System.Windows.Forms.CheckBox();
this.LIM_GPSLCK_REQ = new ArdupilotMega.Controls.MavlinkCheckBox();
this.LIM_FNC_REQ = new ArdupilotMega.Controls.MavlinkCheckBox();
this.LIM_ALT_REQ = new ArdupilotMega.Controls.MavlinkCheckBox();
this.groupBox4 = new System.Windows.Forms.GroupBox();
this.LIM_REQUIRED = new System.Windows.Forms.CheckBox();
this.LIM_REQUIRED = new ArdupilotMega.Controls.MavlinkCheckBox();
this.myLabel4 = new ArdupilotMega.Controls.MyLabel();
this.LIM_CHANNEL = new System.Windows.Forms.NumericUpDown();
this.myLabel3 = new ArdupilotMega.Controls.MyLabel();
this.LIM_FNC_RAD = new System.Windows.Forms.NumericUpDown();
this.LIM_FNC_SMPL = new System.Windows.Forms.CheckBox();
this.LIM_FNC_SMPL = new ArdupilotMega.Controls.MavlinkCheckBox();
this.groupBox3 = new System.Windows.Forms.GroupBox();
this.LIM_GPSLCK_ON = new System.Windows.Forms.CheckBox();
this.LIM_GPSLCK_ON = new ArdupilotMega.Controls.MavlinkCheckBox();
this.groupBox2 = new System.Windows.Forms.GroupBox();
this.LIM_ALT_ON = new System.Windows.Forms.CheckBox();
this.LIM_ALT_ON = new ArdupilotMega.Controls.MavlinkCheckBox();
this.myLabel1 = new ArdupilotMega.Controls.MyLabel();
this.LIM_ALT_MAX = new System.Windows.Forms.NumericUpDown();
this.myLabel2 = new ArdupilotMega.Controls.MyLabel();
@ -281,28 +281,28 @@
#endregion
private System.Windows.Forms.LinkLabel LNK_wiki;
private System.Windows.Forms.CheckBox LIM_ENABLED;
private ArdupilotMega.Controls.MavlinkCheckBox LIM_ENABLED;
private System.Windows.Forms.GroupBox groupBox1;
private Controls.MyLabel myLabel2;
private Controls.MyLabel myLabel1;
private System.Windows.Forms.NumericUpDown LIM_ALT_MAX;
private System.Windows.Forms.NumericUpDown LIM_ALT_MIN;
private System.Windows.Forms.GroupBox groupBox2;
private System.Windows.Forms.CheckBox LIM_ALT_ON;
private ArdupilotMega.Controls.MavlinkCheckBox LIM_ALT_ON;
private System.Windows.Forms.GroupBox groupBox3;
private System.Windows.Forms.CheckBox LIM_GPSLCK_ON;
private ArdupilotMega.Controls.MavlinkCheckBox LIM_GPSLCK_ON;
private System.Windows.Forms.GroupBox groupBox4;
private Controls.MyLabel myLabel3;
private System.Windows.Forms.NumericUpDown LIM_FNC_RAD;
private System.Windows.Forms.CheckBox LIM_FNC_SMPL;
private ArdupilotMega.Controls.MavlinkCheckBox LIM_FNC_SMPL;
private Controls.MyLabel myLabel4;
private System.Windows.Forms.NumericUpDown LIM_CHANNEL;
private System.Windows.Forms.CheckBox LIM_REQUIRED;
private ArdupilotMega.Controls.MavlinkCheckBox LIM_REQUIRED;
private System.Windows.Forms.GroupBox groupBox5;
private System.Windows.Forms.CheckBox LIM_FNC_REQ;
private System.Windows.Forms.CheckBox LIM_ALT_REQ;
private ArdupilotMega.Controls.MavlinkCheckBox LIM_FNC_REQ;
private ArdupilotMega.Controls.MavlinkCheckBox LIM_ALT_REQ;
private System.Windows.Forms.TextBox textBox1;
private System.Windows.Forms.CheckBox LIM_GPSLCK_REQ;
private ArdupilotMega.Controls.MavlinkCheckBox LIM_GPSLCK_REQ;
}
}

View File

@ -25,8 +25,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
{
#if MAVLINK10
Log.Info("Sending level command (mavlink 1.0)");
int fixme; // needs to be accel only
MainV2.comPort.doCommand(MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION,1,1,1,1,1,1,1);
MainV2.comPort.doCommand(MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION,1,0,0,0,0,0,0);
#else
Log.Info("Sending level command (mavlink 0.9)");
MainV2.comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_CALIBRATE_ACC);

View File

@ -181,7 +181,6 @@
// label5
//
resources.ApplyResources(this.label5, "label5");
this.label5.ForeColor = System.Drawing.SystemColors.ControlText;
this.label5.Name = "label5";
//
// groupBox2
@ -193,7 +192,6 @@
// label1
//
resources.ApplyResources(this.label1, "label1");
this.label1.ForeColor = System.Drawing.SystemColors.ControlText;
this.label1.Name = "label1";
//
// groupBox1
@ -205,7 +203,6 @@
// label2
//
resources.ApplyResources(this.label2, "label2");
this.label2.ForeColor = System.Drawing.SystemColors.ControlText;
this.label2.Name = "label2";
//
// groupBox3
@ -217,7 +214,6 @@
// label3
//
resources.ApplyResources(this.label3, "label3");
this.label3.ForeColor = System.Drawing.SystemColors.ControlText;
this.label3.Name = "label3";
//
// groupBox4

View File

@ -139,7 +139,7 @@
<value>BUT_MagCalibrationLive</value>
</data>
<data name="&gt;&gt;BUT_MagCalibrationLive.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4589.38394, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4592.29704, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_MagCalibrationLive.Parent" xml:space="preserve">
<value>$this</value>
@ -214,7 +214,7 @@
<value>NoControl</value>
</data>
<data name="CHK_enableoptflow.Location" type="System.Drawing.Point, System.Drawing">
<value>108, 327</value>
<value>92, 357</value>
</data>
<data name="CHK_enableoptflow.Size" type="System.Drawing.Size, System.Drawing">
<value>134, 19</value>
@ -223,7 +223,7 @@
<value>44</value>
</data>
<data name="CHK_enableoptflow.Text" xml:space="preserve">
<value>Enable Optical Flow</value>
<value>Enable</value>
</data>
<data name="&gt;&gt;CHK_enableoptflow.Name" xml:space="preserve">
<value>CHK_enableoptflow</value>
@ -352,7 +352,7 @@
<value>NoControl</value>
</data>
<data name="CHK_enableairspeed.Location" type="System.Drawing.Point, System.Drawing">
<value>108, 222</value>
<value>92, 249</value>
</data>
<data name="CHK_enableairspeed.Size" type="System.Drawing.Size, System.Drawing">
<value>103, 17</value>
@ -361,7 +361,7 @@
<value>39</value>
</data>
<data name="CHK_enableairspeed.Text" xml:space="preserve">
<value>Enable Airspeed</value>
<value>Enable</value>
</data>
<data name="&gt;&gt;CHK_enableairspeed.Name" xml:space="preserve">
<value>CHK_enableairspeed</value>
@ -382,7 +382,7 @@
<value>NoControl</value>
</data>
<data name="CHK_enablesonar.Location" type="System.Drawing.Point, System.Drawing">
<value>108, 114</value>
<value>92, 141</value>
</data>
<data name="CHK_enablesonar.Size" type="System.Drawing.Size, System.Drawing">
<value>90, 17</value>
@ -391,7 +391,7 @@
<value>40</value>
</data>
<data name="CHK_enablesonar.Text" xml:space="preserve">
<value>Enable Sonar</value>
<value>Enable</value>
</data>
<data name="&gt;&gt;CHK_enablesonar.Name" xml:space="preserve">
<value>CHK_enablesonar</value>
@ -412,16 +412,16 @@
<value>NoControl</value>
</data>
<data name="CHK_enablecompass.Location" type="System.Drawing.Point, System.Drawing">
<value>108, 6</value>
<value>92, 33</value>
</data>
<data name="CHK_enablecompass.Size" type="System.Drawing.Size, System.Drawing">
<value>105, 17</value>
<value>82, 17</value>
</data>
<data name="CHK_enablecompass.TabIndex" type="System.Int32, mscorlib">
<value>41</value>
</data>
<data name="CHK_enablecompass.Text" xml:space="preserve">
<value>Enable Compass</value>
<value>Enable</value>
</data>
<data name="&gt;&gt;CHK_enablecompass.Name" xml:space="preserve">
<value>CHK_enablecompass</value>
@ -541,7 +541,7 @@
<value>BUT_MagCalibrationLog</value>
</data>
<data name="&gt;&gt;BUT_MagCalibrationLog.Type" xml:space="preserve">
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4589.38394, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4592.29704, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_MagCalibrationLog.Parent" xml:space="preserve">
<value>$this</value>
@ -556,7 +556,7 @@
<value>NoControl</value>
</data>
<data name="CHK_autodec.Location" type="System.Drawing.Point, System.Drawing">
<value>92, 50</value>
<value>92, 55</value>
</data>
<data name="CHK_autodec.Size" type="System.Drawing.Size, System.Drawing">
<value>82, 17</value>
@ -579,9 +579,6 @@
<data name="&gt;&gt;CHK_autodec.ZOrder" xml:space="preserve">
<value>12</value>
</data>
<data name="label5.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label5.Font" type="System.Drawing.Font, System.Drawing">
<value>Microsoft Sans Serif, 12pt</value>
</data>
@ -633,9 +630,6 @@
<data name="&gt;&gt;groupBox2.ZOrder" xml:space="preserve">
<value>11</value>
</data>
<data name="label1.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label1.Font" type="System.Drawing.Font, System.Drawing">
<value>Microsoft Sans Serif, 12pt</value>
</data>
@ -690,9 +684,6 @@
<data name="&gt;&gt;groupBox1.ZOrder" xml:space="preserve">
<value>8</value>
</data>
<data name="label2.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label2.Font" type="System.Drawing.Font, System.Drawing">
<value>Microsoft Sans Serif, 12pt</value>
</data>
@ -747,9 +738,6 @@
<data name="&gt;&gt;groupBox3.ZOrder" xml:space="preserve">
<value>5</value>
</data>
<data name="label3.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label3.Font" type="System.Drawing.Font, System.Drawing">
<value>Microsoft Sans Serif, 12pt</value>
</data>

View File

@ -43,76 +43,114 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
LNK_wiki.MouseLeave += (s, e) => FadeLinkTo((LinkLabel)s, Color.WhiteSmoke);
SetErrorMessageOpacity();
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
mavlinkComboBoxTilt.Items.AddRange(Enum.GetNames(typeof(Channelap)));
mavlinkComboBoxRoll.Items.AddRange(Enum.GetNames(typeof(Channelap)));
mavlinkComboBoxPan.Items.AddRange(Enum.GetNames(typeof(Channelap)));
}
else
{
mavlinkComboBoxTilt.Items.AddRange(Enum.GetNames(typeof(Channelac)));
mavlinkComboBoxRoll.Items.AddRange(Enum.GetNames(typeof(Channelac)));
mavlinkComboBoxPan.Items.AddRange(Enum.GetNames(typeof(Channelac)));
}
}
// 0 = disabled 1 = enabled
enum Channelap
{
Disable = 0,
CH_5 = 1,
CH_6 = 1,
CH_7 = 1,
CH_8 = 1
RC5 = 1,
RC6 = 1,
RC7 = 1,
RC8 = 1
}
// 0 = disabled 1 = enabled
enum Channelac
{
Disable = 0,
CAM_P = 7,
CAM_R = 8,
CAM_Y = 6
CAM_P = 1,
CAM_R = 1,
CAM_Y = 1
}
public void Activate()
{
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
foreach (string item in MainV2.comPort.param.Keys)
{
mavlinkComboBoxTilt.setup(typeof(Channelap), "MNT_STAB_PITCH", MainV2.comPort.param);
mavlinkComboBoxRoll.setup(typeof(Channelap), "MNT_STAB_ROLL", MainV2.comPort.param);
mavlinkComboBoxPan.setup(typeof(Channelap), "MNT_STAB_YAW", MainV2.comPort.param);
}
else
{
mavlinkComboBoxTilt.setup(typeof(Channelac), "CAM_P_FUNCTION", MainV2.comPort.param, "MNT_STAB_PITCH");
mavlinkComboBoxRoll.setup(typeof(Channelac), "CAM_R_FUNCTION", MainV2.comPort.param, "MNT_STAB_ROLL");
mavlinkComboBoxPan.setup(typeof(Channelac), "CAM_Y_FUNCTION", MainV2.comPort.param, "MNT_STAB_YAW");
if (item.EndsWith("_FUNCTION"))
{
switch (MainV2.comPort.param[item].ToString())
{
case "6":
mavlinkComboBoxPan.Text = item.Replace("_FUNCTION", "");
break;
case "7":
mavlinkComboBoxTilt.Text = item.Replace("_FUNCTION", "");
break;
case "8":
mavlinkComboBoxRoll.Text = item.Replace("_FUNCTION", "");
break;
default:
break;
}
}
}
updatePitch();
updateRoll();
updateYaw();
}
void updatePitch()
{
// pitch
mavlinkNumericUpDown11.setup(800, 2200, 1, 1, mavlinkComboBoxTilt.Text +"_MIN", MainV2.comPort.param);
mavlinkNumericUpDown12.setup(800, 2200, 1, 1, mavlinkComboBoxTilt.Text + "_MAX", MainV2.comPort.param);
mavlinkNumericUpDown1.setup(-90, 0, 100, 1, mavlinkComboBoxTilt.Text + "_ANGLE_MIN", MainV2.comPort.param);
mavlinkNumericUpDown2.setup(0, 90, 100, 1, mavlinkComboBoxTilt.Text + "_ANGLE_MAX", MainV2.comPort.param);
mavlinkCheckBox1.setup(-1, 1, mavlinkComboBoxTilt.Text + "_REV", MainV2.comPort.param);
if (mavlinkComboBoxTilt.Text != "Disable")
{
MainV2.comPort.setParam(mavlinkComboBoxTilt.Text + "_FUNCTION",7);
MainV2.comPort.setParam("MNT_STAB_PITCH",1);
}
mavlinkNumericUpDownTSM.setup(800, 2200, 1, 1, mavlinkComboBoxTilt.Text +"_MIN", MainV2.comPort.param);
mavlinkNumericUpDownTSMX.setup(800, 2200, 1, 1, mavlinkComboBoxTilt.Text + "_MAX", MainV2.comPort.param);
mavlinkNumericUpDownTAM.setup(-90, 0, 100, 1, mavlinkComboBoxTilt.Text + "_ANGLE_MIN", MainV2.comPort.param);
mavlinkNumericUpDownTAMX.setup(0, 90, 100, 1, mavlinkComboBoxTilt.Text + "_ANGLE_MAX", MainV2.comPort.param);
mavlinkCheckBoxTR.setup(-1, 1, mavlinkComboBoxTilt.Text + "_REV", MainV2.comPort.param);
}
void updateRoll()
{
// roll
mavlinkNumericUpDown5.setup(800, 2200, 1, 1, mavlinkComboBoxRoll.Text +"_MIN", MainV2.comPort.param);
mavlinkNumericUpDown6.setup(800, 2200, 1, 1, mavlinkComboBoxRoll.Text + "_MAX", MainV2.comPort.param);
mavlinkNumericUpDown3.setup(-90, 0, 100, 1, mavlinkComboBoxRoll.Text + "_ANGLE_MIN", MainV2.comPort.param);
mavlinkNumericUpDown4.setup(0, 90, 100, 1, mavlinkComboBoxRoll.Text + "_ANGLE_MAX", MainV2.comPort.param);
mavlinkCheckBox2.setup(-1, 1, mavlinkComboBoxRoll.Text + "_REV", MainV2.comPort.param);
if (mavlinkComboBoxRoll.Text != "Disable")
{
MainV2.comPort.setParam(mavlinkComboBoxRoll.Text + "_FUNCTION", 8);
MainV2.comPort.setParam("MNT_STAB_ROLL", 1);
}
mavlinkNumericUpDownRSM.setup(800, 2200, 1, 1, mavlinkComboBoxRoll.Text +"_MIN", MainV2.comPort.param);
mavlinkNumericUpDownRSMX.setup(800, 2200, 1, 1, mavlinkComboBoxRoll.Text + "_MAX", MainV2.comPort.param);
mavlinkNumericUpDownRAM.setup(-90, 0, 100, 1, mavlinkComboBoxRoll.Text + "_ANGLE_MIN", MainV2.comPort.param);
mavlinkNumericUpDownRAMX.setup(0, 90, 100, 1, mavlinkComboBoxRoll.Text + "_ANGLE_MAX", MainV2.comPort.param);
mavlinkCheckBoxRR.setup(-1, 1, mavlinkComboBoxRoll.Text + "_REV", MainV2.comPort.param);
}
void updateYaw()
{
// yaw
mavlinkNumericUpDown9.setup(800, 2200, 1, 1, mavlinkComboBoxPan.Text + "_MIN", MainV2.comPort.param);
mavlinkNumericUpDown10.setup(800, 2200, 1, 1, mavlinkComboBoxPan.Text + "_MAX", MainV2.comPort.param);
mavlinkNumericUpDown7.setup(-90, 0, 100, 1, mavlinkComboBoxPan.Text + "_ANGLE_MIN", MainV2.comPort.param);
mavlinkNumericUpDown8.setup(0, 90, 100, 1, mavlinkComboBoxPan.Text + "_ANGLE_MAX", MainV2.comPort.param);
mavlinkCheckBox3.setup(-1, 1, mavlinkComboBoxPan.Text + "_REV", MainV2.comPort.param);
if (mavlinkComboBoxPan.Text != "Disable")
{
MainV2.comPort.setParam(mavlinkComboBoxPan.Text + "_FUNCTION", 6);
MainV2.comPort.setParam("MNT_STAB_YAW", 1);
}
mavlinkNumericUpDownPSM.setup(800, 2200, 1, 1, mavlinkComboBoxPan.Text + "_MIN", MainV2.comPort.param);
mavlinkNumericUpDownPSMX.setup(800, 2200, 1, 1, mavlinkComboBoxPan.Text + "_MAX", MainV2.comPort.param);
mavlinkNumericUpDownPAM.setup(-90, 0, 100, 1, mavlinkComboBoxPan.Text + "_ANGLE_MIN", MainV2.comPort.param);
mavlinkNumericUpDownPAMX.setup(0, 90, 100, 1, mavlinkComboBoxPan.Text + "_ANGLE_MAX", MainV2.comPort.param);
mavlinkCheckBoxPR.setup(-1, 1, mavlinkComboBoxPan.Text + "_REV", MainV2.comPort.param);
}
private void SetErrorMessageOpacity()

View File

@ -47,54 +47,54 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.label10 = new System.Windows.Forms.Label();
this.label11 = new System.Windows.Forms.Label();
this.label12 = new System.Windows.Forms.Label();
this.mavlinkNumericUpDown3 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDown4 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDownRAM = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDownRAMX = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.label13 = new System.Windows.Forms.Label();
this.label14 = new System.Windows.Forms.Label();
this.mavlinkNumericUpDown5 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDown6 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkCheckBox2 = new ArdupilotMega.Controls.MavlinkCheckBox();
this.mavlinkNumericUpDownRSM = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDownRSMX = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkCheckBoxRR = new ArdupilotMega.Controls.MavlinkCheckBox();
this.label16 = new System.Windows.Forms.Label();
this.label17 = new System.Windows.Forms.Label();
this.label18 = new System.Windows.Forms.Label();
this.label19 = new System.Windows.Forms.Label();
this.mavlinkNumericUpDown7 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDown8 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDownPAM = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDownPAMX = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.label20 = new System.Windows.Forms.Label();
this.label21 = new System.Windows.Forms.Label();
this.mavlinkNumericUpDown9 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDown10 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkCheckBox3 = new ArdupilotMega.Controls.MavlinkCheckBox();
this.mavlinkNumericUpDownPSM = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDownPSMX = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkCheckBoxPR = new ArdupilotMega.Controls.MavlinkCheckBox();
this.label1 = new System.Windows.Forms.Label();
this.label2 = new System.Windows.Forms.Label();
this.label3 = new System.Windows.Forms.Label();
this.label4 = new System.Windows.Forms.Label();
this.mavlinkNumericUpDown1 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDown2 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDownTAM = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDownTAMX = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.label7 = new System.Windows.Forms.Label();
this.label8 = new System.Windows.Forms.Label();
this.mavlinkNumericUpDown11 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDown12 = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkCheckBox1 = new ArdupilotMega.Controls.MavlinkCheckBox();
this.mavlinkComboBoxTilt = new ArdupilotMega.Controls.MavlinkComboBox();
this.mavlinkComboBoxRoll = new ArdupilotMega.Controls.MavlinkComboBox();
this.mavlinkComboBoxPan = new ArdupilotMega.Controls.MavlinkComboBox();
this.mavlinkNumericUpDownTSM = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkNumericUpDownTSMX = new ArdupilotMega.Controls.MavlinkNumericUpDown();
this.mavlinkCheckBoxTR = new ArdupilotMega.Controls.MavlinkCheckBox();
this.mavlinkComboBoxTilt = new System.Windows.Forms.ComboBox();
this.mavlinkComboBoxRoll = new System.Windows.Forms.ComboBox();
this.mavlinkComboBoxPan = new System.Windows.Forms.ComboBox();
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.PBOX_WarningIcon)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown3)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown4)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown5)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown6)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown7)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown8)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown9)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown10)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown1)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown2)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown11)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown12)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRAM)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRAMX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRSM)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRSMX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownPAM)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownPAMX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownPSM)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownPSMX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownTAM)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownTAMX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownTSM)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownTSMX)).BeginInit();
this.SuspendLayout();
//
// pictureBox1
@ -269,60 +269,60 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.label12.TabIndex = 102;
this.label12.Text = "Min";
//
// mavlinkNumericUpDown3
// mavlinkNumericUpDownRAM
//
this.mavlinkNumericUpDown3.Enabled = false;
this.mavlinkNumericUpDown3.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownRAM.Enabled = false;
this.mavlinkNumericUpDownRAM.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown3.Location = new System.Drawing.Point(385, 181);
this.mavlinkNumericUpDown3.Max = 1F;
this.mavlinkNumericUpDown3.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownRAM.Location = new System.Drawing.Point(385, 181);
this.mavlinkNumericUpDownRAM.Max = 1F;
this.mavlinkNumericUpDownRAM.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown3.Min = 0F;
this.mavlinkNumericUpDown3.Name = "mavlinkNumericUpDown3";
this.mavlinkNumericUpDown3.param = null;
this.mavlinkNumericUpDown3.ParamName = null;
this.mavlinkNumericUpDown3.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown3.TabIndex = 101;
this.mavlinkNumericUpDown3.Value = new decimal(new int[] {
this.mavlinkNumericUpDownRAM.Min = 0F;
this.mavlinkNumericUpDownRAM.Name = "mavlinkNumericUpDownRAM";
this.mavlinkNumericUpDownRAM.param = null;
this.mavlinkNumericUpDownRAM.ParamName = null;
this.mavlinkNumericUpDownRAM.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownRAM.TabIndex = 101;
this.mavlinkNumericUpDownRAM.Value = new decimal(new int[] {
1000,
0,
0,
0});
//
// mavlinkNumericUpDown4
// mavlinkNumericUpDownRAMX
//
this.mavlinkNumericUpDown4.Enabled = false;
this.mavlinkNumericUpDown4.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownRAMX.Enabled = false;
this.mavlinkNumericUpDownRAMX.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown4.Location = new System.Drawing.Point(385, 207);
this.mavlinkNumericUpDown4.Max = 1F;
this.mavlinkNumericUpDown4.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownRAMX.Location = new System.Drawing.Point(385, 207);
this.mavlinkNumericUpDownRAMX.Max = 1F;
this.mavlinkNumericUpDownRAMX.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown4.Min = 0F;
this.mavlinkNumericUpDown4.Minimum = new decimal(new int[] {
this.mavlinkNumericUpDownRAMX.Min = 0F;
this.mavlinkNumericUpDownRAMX.Minimum = new decimal(new int[] {
800,
0,
0,
0});
this.mavlinkNumericUpDown4.Name = "mavlinkNumericUpDown4";
this.mavlinkNumericUpDown4.param = null;
this.mavlinkNumericUpDown4.ParamName = null;
this.mavlinkNumericUpDown4.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown4.TabIndex = 100;
this.mavlinkNumericUpDown4.Value = new decimal(new int[] {
this.mavlinkNumericUpDownRAMX.Name = "mavlinkNumericUpDownRAMX";
this.mavlinkNumericUpDownRAMX.param = null;
this.mavlinkNumericUpDownRAMX.ParamName = null;
this.mavlinkNumericUpDownRAMX.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownRAMX.TabIndex = 100;
this.mavlinkNumericUpDownRAMX.Value = new decimal(new int[] {
2000,
0,
0,
@ -348,85 +348,85 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.label14.TabIndex = 98;
this.label14.Text = "Min";
//
// mavlinkNumericUpDown5
// mavlinkNumericUpDownRSM
//
this.mavlinkNumericUpDown5.Enabled = false;
this.mavlinkNumericUpDown5.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownRSM.Enabled = false;
this.mavlinkNumericUpDownRSM.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown5.Location = new System.Drawing.Point(276, 181);
this.mavlinkNumericUpDown5.Max = 1F;
this.mavlinkNumericUpDown5.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownRSM.Location = new System.Drawing.Point(276, 181);
this.mavlinkNumericUpDownRSM.Max = 1F;
this.mavlinkNumericUpDownRSM.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown5.Min = 0F;
this.mavlinkNumericUpDown5.Minimum = new decimal(new int[] {
this.mavlinkNumericUpDownRSM.Min = 0F;
this.mavlinkNumericUpDownRSM.Minimum = new decimal(new int[] {
800,
0,
0,
0});
this.mavlinkNumericUpDown5.Name = "mavlinkNumericUpDown5";
this.mavlinkNumericUpDown5.param = null;
this.mavlinkNumericUpDown5.ParamName = null;
this.mavlinkNumericUpDown5.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown5.TabIndex = 97;
this.mavlinkNumericUpDown5.Value = new decimal(new int[] {
this.mavlinkNumericUpDownRSM.Name = "mavlinkNumericUpDownRSM";
this.mavlinkNumericUpDownRSM.param = null;
this.mavlinkNumericUpDownRSM.ParamName = null;
this.mavlinkNumericUpDownRSM.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownRSM.TabIndex = 97;
this.mavlinkNumericUpDownRSM.Value = new decimal(new int[] {
1000,
0,
0,
0});
//
// mavlinkNumericUpDown6
// mavlinkNumericUpDownRSMX
//
this.mavlinkNumericUpDown6.Enabled = false;
this.mavlinkNumericUpDown6.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownRSMX.Enabled = false;
this.mavlinkNumericUpDownRSMX.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown6.Location = new System.Drawing.Point(276, 207);
this.mavlinkNumericUpDown6.Max = 1F;
this.mavlinkNumericUpDown6.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownRSMX.Location = new System.Drawing.Point(276, 207);
this.mavlinkNumericUpDownRSMX.Max = 1F;
this.mavlinkNumericUpDownRSMX.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown6.Min = 0F;
this.mavlinkNumericUpDown6.Minimum = new decimal(new int[] {
this.mavlinkNumericUpDownRSMX.Min = 0F;
this.mavlinkNumericUpDownRSMX.Minimum = new decimal(new int[] {
800,
0,
0,
0});
this.mavlinkNumericUpDown6.Name = "mavlinkNumericUpDown6";
this.mavlinkNumericUpDown6.param = null;
this.mavlinkNumericUpDown6.ParamName = null;
this.mavlinkNumericUpDown6.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown6.TabIndex = 96;
this.mavlinkNumericUpDown6.Value = new decimal(new int[] {
this.mavlinkNumericUpDownRSMX.Name = "mavlinkNumericUpDownRSMX";
this.mavlinkNumericUpDownRSMX.param = null;
this.mavlinkNumericUpDownRSMX.ParamName = null;
this.mavlinkNumericUpDownRSMX.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownRSMX.TabIndex = 96;
this.mavlinkNumericUpDownRSMX.Value = new decimal(new int[] {
2000,
0,
0,
0});
//
// mavlinkCheckBox2
// mavlinkCheckBoxRR
//
this.mavlinkCheckBox2.AutoSize = true;
this.mavlinkCheckBox2.Enabled = false;
this.mavlinkCheckBox2.ForeColor = System.Drawing.Color.FromArgb(((int)(((byte)(224)))), ((int)(((byte)(224)))), ((int)(((byte)(224)))));
this.mavlinkCheckBox2.Location = new System.Drawing.Point(267, 233);
this.mavlinkCheckBox2.Name = "mavlinkCheckBox2";
this.mavlinkCheckBox2.OffValue = 0F;
this.mavlinkCheckBox2.OnValue = 1F;
this.mavlinkCheckBox2.param = null;
this.mavlinkCheckBox2.ParamName = null;
this.mavlinkCheckBox2.Size = new System.Drawing.Size(66, 17);
this.mavlinkCheckBox2.TabIndex = 95;
this.mavlinkCheckBox2.Text = "Reverse";
this.mavlinkCheckBox2.UseVisualStyleBackColor = true;
this.mavlinkCheckBoxRR.AutoSize = true;
this.mavlinkCheckBoxRR.Enabled = false;
this.mavlinkCheckBoxRR.ForeColor = System.Drawing.Color.FromArgb(((int)(((byte)(224)))), ((int)(((byte)(224)))), ((int)(((byte)(224)))));
this.mavlinkCheckBoxRR.Location = new System.Drawing.Point(267, 233);
this.mavlinkCheckBoxRR.Name = "mavlinkCheckBoxRR";
this.mavlinkCheckBoxRR.OffValue = 0F;
this.mavlinkCheckBoxRR.OnValue = 1F;
this.mavlinkCheckBoxRR.param = null;
this.mavlinkCheckBoxRR.ParamName = null;
this.mavlinkCheckBoxRR.Size = new System.Drawing.Size(66, 17);
this.mavlinkCheckBoxRR.TabIndex = 95;
this.mavlinkCheckBoxRR.Text = "Reverse";
this.mavlinkCheckBoxRR.UseVisualStyleBackColor = true;
//
// label16
//
@ -468,60 +468,60 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.label19.TabIndex = 113;
this.label19.Text = "Min";
//
// mavlinkNumericUpDown7
// mavlinkNumericUpDownPAM
//
this.mavlinkNumericUpDown7.Enabled = false;
this.mavlinkNumericUpDown7.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownPAM.Enabled = false;
this.mavlinkNumericUpDownPAM.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown7.Location = new System.Drawing.Point(385, 305);
this.mavlinkNumericUpDown7.Max = 1F;
this.mavlinkNumericUpDown7.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownPAM.Location = new System.Drawing.Point(385, 305);
this.mavlinkNumericUpDownPAM.Max = 1F;
this.mavlinkNumericUpDownPAM.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown7.Min = 0F;
this.mavlinkNumericUpDown7.Name = "mavlinkNumericUpDown7";
this.mavlinkNumericUpDown7.param = null;
this.mavlinkNumericUpDown7.ParamName = null;
this.mavlinkNumericUpDown7.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown7.TabIndex = 112;
this.mavlinkNumericUpDown7.Value = new decimal(new int[] {
this.mavlinkNumericUpDownPAM.Min = 0F;
this.mavlinkNumericUpDownPAM.Name = "mavlinkNumericUpDownPAM";
this.mavlinkNumericUpDownPAM.param = null;
this.mavlinkNumericUpDownPAM.ParamName = null;
this.mavlinkNumericUpDownPAM.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownPAM.TabIndex = 112;
this.mavlinkNumericUpDownPAM.Value = new decimal(new int[] {
1000,
0,
0,
0});
//
// mavlinkNumericUpDown8
// mavlinkNumericUpDownPAMX
//
this.mavlinkNumericUpDown8.Enabled = false;
this.mavlinkNumericUpDown8.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownPAMX.Enabled = false;
this.mavlinkNumericUpDownPAMX.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown8.Location = new System.Drawing.Point(385, 331);
this.mavlinkNumericUpDown8.Max = 1F;
this.mavlinkNumericUpDown8.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownPAMX.Location = new System.Drawing.Point(385, 331);
this.mavlinkNumericUpDownPAMX.Max = 1F;
this.mavlinkNumericUpDownPAMX.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown8.Min = 0F;
this.mavlinkNumericUpDown8.Minimum = new decimal(new int[] {
this.mavlinkNumericUpDownPAMX.Min = 0F;
this.mavlinkNumericUpDownPAMX.Minimum = new decimal(new int[] {
800,
0,
0,
0});
this.mavlinkNumericUpDown8.Name = "mavlinkNumericUpDown8";
this.mavlinkNumericUpDown8.param = null;
this.mavlinkNumericUpDown8.ParamName = null;
this.mavlinkNumericUpDown8.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown8.TabIndex = 111;
this.mavlinkNumericUpDown8.Value = new decimal(new int[] {
this.mavlinkNumericUpDownPAMX.Name = "mavlinkNumericUpDownPAMX";
this.mavlinkNumericUpDownPAMX.param = null;
this.mavlinkNumericUpDownPAMX.ParamName = null;
this.mavlinkNumericUpDownPAMX.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownPAMX.TabIndex = 111;
this.mavlinkNumericUpDownPAMX.Value = new decimal(new int[] {
2000,
0,
0,
@ -547,85 +547,85 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.label21.TabIndex = 109;
this.label21.Text = "Min";
//
// mavlinkNumericUpDown9
// mavlinkNumericUpDownPSM
//
this.mavlinkNumericUpDown9.Enabled = false;
this.mavlinkNumericUpDown9.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownPSM.Enabled = false;
this.mavlinkNumericUpDownPSM.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown9.Location = new System.Drawing.Point(276, 305);
this.mavlinkNumericUpDown9.Max = 1F;
this.mavlinkNumericUpDown9.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownPSM.Location = new System.Drawing.Point(276, 305);
this.mavlinkNumericUpDownPSM.Max = 1F;
this.mavlinkNumericUpDownPSM.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown9.Min = 0F;
this.mavlinkNumericUpDown9.Minimum = new decimal(new int[] {
this.mavlinkNumericUpDownPSM.Min = 0F;
this.mavlinkNumericUpDownPSM.Minimum = new decimal(new int[] {
800,
0,
0,
0});
this.mavlinkNumericUpDown9.Name = "mavlinkNumericUpDown9";
this.mavlinkNumericUpDown9.param = null;
this.mavlinkNumericUpDown9.ParamName = null;
this.mavlinkNumericUpDown9.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown9.TabIndex = 108;
this.mavlinkNumericUpDown9.Value = new decimal(new int[] {
this.mavlinkNumericUpDownPSM.Name = "mavlinkNumericUpDownPSM";
this.mavlinkNumericUpDownPSM.param = null;
this.mavlinkNumericUpDownPSM.ParamName = null;
this.mavlinkNumericUpDownPSM.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownPSM.TabIndex = 108;
this.mavlinkNumericUpDownPSM.Value = new decimal(new int[] {
1000,
0,
0,
0});
//
// mavlinkNumericUpDown10
// mavlinkNumericUpDownPSMX
//
this.mavlinkNumericUpDown10.Enabled = false;
this.mavlinkNumericUpDown10.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownPSMX.Enabled = false;
this.mavlinkNumericUpDownPSMX.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown10.Location = new System.Drawing.Point(276, 331);
this.mavlinkNumericUpDown10.Max = 1F;
this.mavlinkNumericUpDown10.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownPSMX.Location = new System.Drawing.Point(276, 331);
this.mavlinkNumericUpDownPSMX.Max = 1F;
this.mavlinkNumericUpDownPSMX.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown10.Min = 0F;
this.mavlinkNumericUpDown10.Minimum = new decimal(new int[] {
this.mavlinkNumericUpDownPSMX.Min = 0F;
this.mavlinkNumericUpDownPSMX.Minimum = new decimal(new int[] {
800,
0,
0,
0});
this.mavlinkNumericUpDown10.Name = "mavlinkNumericUpDown10";
this.mavlinkNumericUpDown10.param = null;
this.mavlinkNumericUpDown10.ParamName = null;
this.mavlinkNumericUpDown10.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown10.TabIndex = 107;
this.mavlinkNumericUpDown10.Value = new decimal(new int[] {
this.mavlinkNumericUpDownPSMX.Name = "mavlinkNumericUpDownPSMX";
this.mavlinkNumericUpDownPSMX.param = null;
this.mavlinkNumericUpDownPSMX.ParamName = null;
this.mavlinkNumericUpDownPSMX.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownPSMX.TabIndex = 107;
this.mavlinkNumericUpDownPSMX.Value = new decimal(new int[] {
2000,
0,
0,
0});
//
// mavlinkCheckBox3
// mavlinkCheckBoxPR
//
this.mavlinkCheckBox3.AutoSize = true;
this.mavlinkCheckBox3.Enabled = false;
this.mavlinkCheckBox3.ForeColor = System.Drawing.Color.FromArgb(((int)(((byte)(224)))), ((int)(((byte)(224)))), ((int)(((byte)(224)))));
this.mavlinkCheckBox3.Location = new System.Drawing.Point(267, 357);
this.mavlinkCheckBox3.Name = "mavlinkCheckBox3";
this.mavlinkCheckBox3.OffValue = 0F;
this.mavlinkCheckBox3.OnValue = 1F;
this.mavlinkCheckBox3.param = null;
this.mavlinkCheckBox3.ParamName = null;
this.mavlinkCheckBox3.Size = new System.Drawing.Size(66, 17);
this.mavlinkCheckBox3.TabIndex = 106;
this.mavlinkCheckBox3.Text = "Reverse";
this.mavlinkCheckBox3.UseVisualStyleBackColor = true;
this.mavlinkCheckBoxPR.AutoSize = true;
this.mavlinkCheckBoxPR.Enabled = false;
this.mavlinkCheckBoxPR.ForeColor = System.Drawing.Color.FromArgb(((int)(((byte)(224)))), ((int)(((byte)(224)))), ((int)(((byte)(224)))));
this.mavlinkCheckBoxPR.Location = new System.Drawing.Point(267, 357);
this.mavlinkCheckBoxPR.Name = "mavlinkCheckBoxPR";
this.mavlinkCheckBoxPR.OffValue = 0F;
this.mavlinkCheckBoxPR.OnValue = 1F;
this.mavlinkCheckBoxPR.param = null;
this.mavlinkCheckBoxPR.ParamName = null;
this.mavlinkCheckBoxPR.Size = new System.Drawing.Size(66, 17);
this.mavlinkCheckBoxPR.TabIndex = 106;
this.mavlinkCheckBoxPR.Text = "Reverse";
this.mavlinkCheckBoxPR.UseVisualStyleBackColor = true;
//
// label1
//
@ -667,60 +667,60 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.label4.TabIndex = 124;
this.label4.Text = "Min";
//
// mavlinkNumericUpDown1
// mavlinkNumericUpDownTAM
//
this.mavlinkNumericUpDown1.Enabled = false;
this.mavlinkNumericUpDown1.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownTAM.Enabled = false;
this.mavlinkNumericUpDownTAM.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown1.Location = new System.Drawing.Point(385, 54);
this.mavlinkNumericUpDown1.Max = 1F;
this.mavlinkNumericUpDown1.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownTAM.Location = new System.Drawing.Point(385, 54);
this.mavlinkNumericUpDownTAM.Max = 1F;
this.mavlinkNumericUpDownTAM.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown1.Min = 0F;
this.mavlinkNumericUpDown1.Name = "mavlinkNumericUpDown1";
this.mavlinkNumericUpDown1.param = null;
this.mavlinkNumericUpDown1.ParamName = null;
this.mavlinkNumericUpDown1.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown1.TabIndex = 123;
this.mavlinkNumericUpDown1.Value = new decimal(new int[] {
this.mavlinkNumericUpDownTAM.Min = 0F;
this.mavlinkNumericUpDownTAM.Name = "mavlinkNumericUpDownTAM";
this.mavlinkNumericUpDownTAM.param = null;
this.mavlinkNumericUpDownTAM.ParamName = null;
this.mavlinkNumericUpDownTAM.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownTAM.TabIndex = 123;
this.mavlinkNumericUpDownTAM.Value = new decimal(new int[] {
1000,
0,
0,
0});
//
// mavlinkNumericUpDown2
// mavlinkNumericUpDownTAMX
//
this.mavlinkNumericUpDown2.Enabled = false;
this.mavlinkNumericUpDown2.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownTAMX.Enabled = false;
this.mavlinkNumericUpDownTAMX.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown2.Location = new System.Drawing.Point(385, 80);
this.mavlinkNumericUpDown2.Max = 1F;
this.mavlinkNumericUpDown2.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownTAMX.Location = new System.Drawing.Point(385, 80);
this.mavlinkNumericUpDownTAMX.Max = 1F;
this.mavlinkNumericUpDownTAMX.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown2.Min = 0F;
this.mavlinkNumericUpDown2.Minimum = new decimal(new int[] {
this.mavlinkNumericUpDownTAMX.Min = 0F;
this.mavlinkNumericUpDownTAMX.Minimum = new decimal(new int[] {
800,
0,
0,
0});
this.mavlinkNumericUpDown2.Name = "mavlinkNumericUpDown2";
this.mavlinkNumericUpDown2.param = null;
this.mavlinkNumericUpDown2.ParamName = null;
this.mavlinkNumericUpDown2.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown2.TabIndex = 122;
this.mavlinkNumericUpDown2.Value = new decimal(new int[] {
this.mavlinkNumericUpDownTAMX.Name = "mavlinkNumericUpDownTAMX";
this.mavlinkNumericUpDownTAMX.param = null;
this.mavlinkNumericUpDownTAMX.ParamName = null;
this.mavlinkNumericUpDownTAMX.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownTAMX.TabIndex = 122;
this.mavlinkNumericUpDownTAMX.Value = new decimal(new int[] {
2000,
0,
0,
@ -746,95 +746,92 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.label8.TabIndex = 120;
this.label8.Text = "Min";
//
// mavlinkNumericUpDown11
// mavlinkNumericUpDownTSM
//
this.mavlinkNumericUpDown11.Enabled = false;
this.mavlinkNumericUpDown11.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownTSM.Enabled = false;
this.mavlinkNumericUpDownTSM.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown11.Location = new System.Drawing.Point(276, 54);
this.mavlinkNumericUpDown11.Max = 1F;
this.mavlinkNumericUpDown11.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownTSM.Location = new System.Drawing.Point(276, 54);
this.mavlinkNumericUpDownTSM.Max = 1F;
this.mavlinkNumericUpDownTSM.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown11.Min = 0F;
this.mavlinkNumericUpDown11.Minimum = new decimal(new int[] {
this.mavlinkNumericUpDownTSM.Min = 0F;
this.mavlinkNumericUpDownTSM.Minimum = new decimal(new int[] {
800,
0,
0,
0});
this.mavlinkNumericUpDown11.Name = "mavlinkNumericUpDown11";
this.mavlinkNumericUpDown11.param = null;
this.mavlinkNumericUpDown11.ParamName = null;
this.mavlinkNumericUpDown11.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown11.TabIndex = 119;
this.mavlinkNumericUpDown11.Value = new decimal(new int[] {
this.mavlinkNumericUpDownTSM.Name = "mavlinkNumericUpDownTSM";
this.mavlinkNumericUpDownTSM.param = null;
this.mavlinkNumericUpDownTSM.ParamName = null;
this.mavlinkNumericUpDownTSM.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownTSM.TabIndex = 119;
this.mavlinkNumericUpDownTSM.Value = new decimal(new int[] {
1000,
0,
0,
0});
//
// mavlinkNumericUpDown12
// mavlinkNumericUpDownTSMX
//
this.mavlinkNumericUpDown12.Enabled = false;
this.mavlinkNumericUpDown12.Increment = new decimal(new int[] {
this.mavlinkNumericUpDownTSMX.Enabled = false;
this.mavlinkNumericUpDownTSMX.Increment = new decimal(new int[] {
10,
0,
0,
0});
this.mavlinkNumericUpDown12.Location = new System.Drawing.Point(276, 80);
this.mavlinkNumericUpDown12.Max = 1F;
this.mavlinkNumericUpDown12.Maximum = new decimal(new int[] {
this.mavlinkNumericUpDownTSMX.Location = new System.Drawing.Point(276, 80);
this.mavlinkNumericUpDownTSMX.Max = 1F;
this.mavlinkNumericUpDownTSMX.Maximum = new decimal(new int[] {
2200,
0,
0,
0});
this.mavlinkNumericUpDown12.Min = 0F;
this.mavlinkNumericUpDown12.Minimum = new decimal(new int[] {
this.mavlinkNumericUpDownTSMX.Min = 0F;
this.mavlinkNumericUpDownTSMX.Minimum = new decimal(new int[] {
800,
0,
0,
0});
this.mavlinkNumericUpDown12.Name = "mavlinkNumericUpDown12";
this.mavlinkNumericUpDown12.param = null;
this.mavlinkNumericUpDown12.ParamName = null;
this.mavlinkNumericUpDown12.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDown12.TabIndex = 118;
this.mavlinkNumericUpDown12.Value = new decimal(new int[] {
this.mavlinkNumericUpDownTSMX.Name = "mavlinkNumericUpDownTSMX";
this.mavlinkNumericUpDownTSMX.param = null;
this.mavlinkNumericUpDownTSMX.ParamName = null;
this.mavlinkNumericUpDownTSMX.Size = new System.Drawing.Size(59, 20);
this.mavlinkNumericUpDownTSMX.TabIndex = 118;
this.mavlinkNumericUpDownTSMX.Value = new decimal(new int[] {
2000,
0,
0,
0});
//
// mavlinkCheckBox1
// mavlinkCheckBoxTR
//
this.mavlinkCheckBox1.AutoSize = true;
this.mavlinkCheckBox1.Enabled = false;
this.mavlinkCheckBox1.ForeColor = System.Drawing.Color.FromArgb(((int)(((byte)(224)))), ((int)(((byte)(224)))), ((int)(((byte)(224)))));
this.mavlinkCheckBox1.Location = new System.Drawing.Point(267, 106);
this.mavlinkCheckBox1.Name = "mavlinkCheckBox1";
this.mavlinkCheckBox1.OffValue = 0F;
this.mavlinkCheckBox1.OnValue = 1F;
this.mavlinkCheckBox1.param = null;
this.mavlinkCheckBox1.ParamName = null;
this.mavlinkCheckBox1.Size = new System.Drawing.Size(66, 17);
this.mavlinkCheckBox1.TabIndex = 117;
this.mavlinkCheckBox1.Text = "Reverse";
this.mavlinkCheckBox1.UseVisualStyleBackColor = true;
this.mavlinkCheckBoxTR.AutoSize = true;
this.mavlinkCheckBoxTR.Enabled = false;
this.mavlinkCheckBoxTR.ForeColor = System.Drawing.Color.FromArgb(((int)(((byte)(224)))), ((int)(((byte)(224)))), ((int)(((byte)(224)))));
this.mavlinkCheckBoxTR.Location = new System.Drawing.Point(267, 106);
this.mavlinkCheckBoxTR.Name = "mavlinkCheckBoxTR";
this.mavlinkCheckBoxTR.OffValue = 0F;
this.mavlinkCheckBoxTR.OnValue = 1F;
this.mavlinkCheckBoxTR.param = null;
this.mavlinkCheckBoxTR.ParamName = null;
this.mavlinkCheckBoxTR.Size = new System.Drawing.Size(66, 17);
this.mavlinkCheckBoxTR.TabIndex = 117;
this.mavlinkCheckBoxTR.Text = "Reverse";
this.mavlinkCheckBoxTR.UseVisualStyleBackColor = true;
//
// mavlinkComboBoxTilt
//
this.mavlinkComboBoxTilt.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
this.mavlinkComboBoxTilt.Enabled = false;
this.mavlinkComboBoxTilt.FormattingEnabled = true;
this.mavlinkComboBoxTilt.Location = new System.Drawing.Point(71, 3);
this.mavlinkComboBoxTilt.Name = "mavlinkComboBoxTilt";
this.mavlinkComboBoxTilt.param = null;
this.mavlinkComboBoxTilt.ParamName = null;
this.mavlinkComboBoxTilt.Size = new System.Drawing.Size(121, 21);
this.mavlinkComboBoxTilt.TabIndex = 128;
this.mavlinkComboBoxTilt.SelectedIndexChanged += new System.EventHandler(this.mavlinkComboBox_SelectedIndexChanged);
@ -842,12 +839,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
// mavlinkComboBoxRoll
//
this.mavlinkComboBoxRoll.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
this.mavlinkComboBoxRoll.Enabled = false;
this.mavlinkComboBoxRoll.FormattingEnabled = true;
this.mavlinkComboBoxRoll.Location = new System.Drawing.Point(71, 131);
this.mavlinkComboBoxRoll.Name = "mavlinkComboBoxRoll";
this.mavlinkComboBoxRoll.param = null;
this.mavlinkComboBoxRoll.ParamName = null;
this.mavlinkComboBoxRoll.Size = new System.Drawing.Size(121, 21);
this.mavlinkComboBoxRoll.TabIndex = 129;
this.mavlinkComboBoxRoll.SelectedIndexChanged += new System.EventHandler(this.mavlinkComboBox_SelectedIndexChanged);
@ -855,12 +849,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
// mavlinkComboBoxPan
//
this.mavlinkComboBoxPan.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
this.mavlinkComboBoxPan.Enabled = false;
this.mavlinkComboBoxPan.FormattingEnabled = true;
this.mavlinkComboBoxPan.Location = new System.Drawing.Point(71, 255);
this.mavlinkComboBoxPan.Name = "mavlinkComboBoxPan";
this.mavlinkComboBoxPan.param = null;
this.mavlinkComboBoxPan.ParamName = null;
this.mavlinkComboBoxPan.Size = new System.Drawing.Size(121, 21);
this.mavlinkComboBoxPan.TabIndex = 130;
this.mavlinkComboBoxPan.SelectedIndexChanged += new System.EventHandler(this.mavlinkComboBox_SelectedIndexChanged);
@ -875,35 +866,35 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.Controls.Add(this.label2);
this.Controls.Add(this.label3);
this.Controls.Add(this.label4);
this.Controls.Add(this.mavlinkNumericUpDown1);
this.Controls.Add(this.mavlinkNumericUpDown2);
this.Controls.Add(this.mavlinkNumericUpDownTAM);
this.Controls.Add(this.mavlinkNumericUpDownTAMX);
this.Controls.Add(this.label7);
this.Controls.Add(this.label8);
this.Controls.Add(this.mavlinkNumericUpDown11);
this.Controls.Add(this.mavlinkNumericUpDown12);
this.Controls.Add(this.mavlinkCheckBox1);
this.Controls.Add(this.mavlinkNumericUpDownTSM);
this.Controls.Add(this.mavlinkNumericUpDownTSMX);
this.Controls.Add(this.mavlinkCheckBoxTR);
this.Controls.Add(this.label16);
this.Controls.Add(this.label17);
this.Controls.Add(this.label18);
this.Controls.Add(this.label19);
this.Controls.Add(this.mavlinkNumericUpDown7);
this.Controls.Add(this.mavlinkNumericUpDown8);
this.Controls.Add(this.mavlinkNumericUpDownPAM);
this.Controls.Add(this.mavlinkNumericUpDownPAMX);
this.Controls.Add(this.label20);
this.Controls.Add(this.label21);
this.Controls.Add(this.mavlinkNumericUpDown9);
this.Controls.Add(this.mavlinkNumericUpDown10);
this.Controls.Add(this.mavlinkCheckBox3);
this.Controls.Add(this.mavlinkNumericUpDownPSM);
this.Controls.Add(this.mavlinkNumericUpDownPSMX);
this.Controls.Add(this.mavlinkCheckBoxPR);
this.Controls.Add(this.label9);
this.Controls.Add(this.label10);
this.Controls.Add(this.label11);
this.Controls.Add(this.label12);
this.Controls.Add(this.mavlinkNumericUpDown3);
this.Controls.Add(this.mavlinkNumericUpDown4);
this.Controls.Add(this.mavlinkNumericUpDownRAM);
this.Controls.Add(this.mavlinkNumericUpDownRAMX);
this.Controls.Add(this.label13);
this.Controls.Add(this.label14);
this.Controls.Add(this.mavlinkNumericUpDown5);
this.Controls.Add(this.mavlinkNumericUpDown6);
this.Controls.Add(this.mavlinkCheckBox2);
this.Controls.Add(this.mavlinkNumericUpDownRSM);
this.Controls.Add(this.mavlinkNumericUpDownRSMX);
this.Controls.Add(this.mavlinkCheckBoxRR);
this.Controls.Add(this.label15);
this.Controls.Add(this.groupBox3);
this.Controls.Add(this.pictureBox3);
@ -922,18 +913,18 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.PBOX_WarningIcon)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown3)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown4)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown5)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown6)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown7)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown8)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown9)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown10)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown1)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown2)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown11)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDown12)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRAM)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRAMX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRSM)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownRSMX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownPAM)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownPAMX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownPSM)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownPSMX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownTAM)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownTAMX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownTSM)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.mavlinkNumericUpDownTSMX)).EndInit();
this.ResumeLayout(false);
this.PerformLayout();
@ -957,38 +948,38 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
private System.Windows.Forms.Label label10;
private System.Windows.Forms.Label label11;
private System.Windows.Forms.Label label12;
private MavlinkNumericUpDown mavlinkNumericUpDown3;
private MavlinkNumericUpDown mavlinkNumericUpDown4;
private MavlinkNumericUpDown mavlinkNumericUpDownRAM;
private MavlinkNumericUpDown mavlinkNumericUpDownRAMX;
private System.Windows.Forms.Label label13;
private System.Windows.Forms.Label label14;
private MavlinkNumericUpDown mavlinkNumericUpDown5;
private MavlinkNumericUpDown mavlinkNumericUpDown6;
private MavlinkCheckBox mavlinkCheckBox2;
private MavlinkNumericUpDown mavlinkNumericUpDownRSM;
private MavlinkNumericUpDown mavlinkNumericUpDownRSMX;
private MavlinkCheckBox mavlinkCheckBoxRR;
private System.Windows.Forms.Label label16;
private System.Windows.Forms.Label label17;
private System.Windows.Forms.Label label18;
private System.Windows.Forms.Label label19;
private MavlinkNumericUpDown mavlinkNumericUpDown7;
private MavlinkNumericUpDown mavlinkNumericUpDown8;
private MavlinkNumericUpDown mavlinkNumericUpDownPAM;
private MavlinkNumericUpDown mavlinkNumericUpDownPAMX;
private System.Windows.Forms.Label label20;
private System.Windows.Forms.Label label21;
private MavlinkNumericUpDown mavlinkNumericUpDown9;
private MavlinkNumericUpDown mavlinkNumericUpDown10;
private MavlinkCheckBox mavlinkCheckBox3;
private MavlinkNumericUpDown mavlinkNumericUpDownPSM;
private MavlinkNumericUpDown mavlinkNumericUpDownPSMX;
private MavlinkCheckBox mavlinkCheckBoxPR;
private System.Windows.Forms.Label label1;
private System.Windows.Forms.Label label2;
private System.Windows.Forms.Label label3;
private System.Windows.Forms.Label label4;
private MavlinkNumericUpDown mavlinkNumericUpDown1;
private MavlinkNumericUpDown mavlinkNumericUpDown2;
private MavlinkNumericUpDown mavlinkNumericUpDownTAM;
private MavlinkNumericUpDown mavlinkNumericUpDownTAMX;
private System.Windows.Forms.Label label7;
private System.Windows.Forms.Label label8;
private MavlinkNumericUpDown mavlinkNumericUpDown11;
private MavlinkNumericUpDown mavlinkNumericUpDown12;
private MavlinkCheckBox mavlinkCheckBox1;
private MavlinkComboBox mavlinkComboBoxTilt;
private MavlinkComboBox mavlinkComboBoxRoll;
private MavlinkComboBox mavlinkComboBoxPan;
private MavlinkNumericUpDown mavlinkNumericUpDownTSM;
private MavlinkNumericUpDown mavlinkNumericUpDownTSMX;
private MavlinkCheckBox mavlinkCheckBoxTR;
private System.Windows.Forms.ComboBox mavlinkComboBoxTilt;
private System.Windows.Forms.ComboBox mavlinkComboBoxRoll;
private System.Windows.Forms.ComboBox mavlinkComboBoxPan;
}
}

View File

@ -90,6 +90,8 @@ If you are just setting up 3DR radios, you may continue without connecting.");
/****************************** ArduPlane **************************/
else if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
AddBackstageViewPage(new ConfigMount(), "Camera Gimbal");
AddBackstageViewPage(new ConfigAccelerometerCalibrationPlane(), "ArduPlane Level");
AddBackstageViewPage(new ConfigArduplane(), "ArduPlane Pids");
}

View File

@ -546,12 +546,12 @@ namespace ArdupilotMega.GCSViews
{
try
{
Console.Write(((SerialPort)port).ReadExisting().Replace("\0"," "));
// Console.Write(((SerialPort)port).ReadExisting().Replace("\0"," "));
}
catch { }
System.Threading.Thread.Sleep(1000);
progress.Value = (int)Math.Min(((DateTime.Now - startwait).TotalSeconds / 17 * 100),100);
progress.Refresh();
Application.DoEvents();
}
try
{

View File

@ -512,13 +512,17 @@ namespace ArdupilotMega.GCSViews
//route.Stroke.Width = 5;
//route.Tag = "track";
routes.Routes.Clear();
routes.Routes.Add(route);
updateClearRoutes();
if (waypoints.AddSeconds(10) < DateTime.Now)
{
//Console.WriteLine("Doing FD WP's");
while (gMapControl1.inOnPaint == true)
{
System.Threading.Thread.Sleep(1);
}
polygons.Markers.Clear();
routes.Markers.Clear();
if (MainV2.comPort.logreadmode && MainV2.comPort.logplaybackfile != null)
{
@ -533,6 +537,12 @@ namespace ArdupilotMega.GCSViews
if (plla.Lng == 0 || plla.Lat == 0)
continue;
if (plla.Tag.StartsWith("ROI"))
{
addpolygonmarkerred(plla.Tag, plla.Lng, plla.Lat, (int)plla.Alt, plla.color, routes);
continue;
}
addpolygonmarker(plla.Tag, plla.Lng, plla.Lat, (int)plla.Alt,plla.color,polygons);
}
@ -605,6 +615,19 @@ namespace ArdupilotMega.GCSViews
});
}
// to prevent cross thread calls while in a draw and exception
private void updateClearRoutes()
{
// not async
this.Invoke((System.Windows.Forms.MethodInvoker)delegate()
{
routes.Routes.Clear();
routes.Routes.Add(route);
});
}
private void updatePlayPauseButton(bool playing)
{
if (playing)
@ -718,6 +741,27 @@ namespace ArdupilotMega.GCSViews
catch (Exception) { }
}
private void addpolygonmarkerred(string tag, double lng, double lat, int alt, Color? color, GMapOverlay overlay)
{
try
{
PointLatLng point = new PointLatLng(lat, lng);
GMapMarkerGoogleRed m = new GMapMarkerGoogleRed(point);
m.ToolTipMode = MarkerTooltipMode.Always;
m.ToolTipText = tag;
m.Tag = tag;
GMapMarkerRect mBorders = new GMapMarkerRect(point);
{
mBorders.InnerMarker = m;
}
overlay.Markers.Add(m);
overlay.Markers.Add(mBorders);
}
catch (Exception) { }
}
/// <summary>
/// used to redraw the polygon
/// </summary>
@ -1660,52 +1704,82 @@ namespace ArdupilotMega.GCSViews
if (list1item == null)
{
if (setupPropertyInfo(ref list1item, ((CheckBox)sender).Name, MainV2.cs))
{
list1.Clear();
list1curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list1, Color.Red, SymbolType.None);
}
}
else if (list2item == null)
{
if (setupPropertyInfo(ref list2item, ((CheckBox)sender).Name, MainV2.cs))
{
list2.Clear();
list2curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list2, Color.Blue, SymbolType.None);
}
}
else if (list3item == null)
{
if (setupPropertyInfo(ref list3item, ((CheckBox)sender).Name, MainV2.cs))
{
list3.Clear();
list3curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list3, Color.Green, SymbolType.None);
}
}
else if (list4item == null)
{
if (setupPropertyInfo(ref list4item, ((CheckBox)sender).Name, MainV2.cs))
{
list4.Clear();
list4curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list4, Color.Orange, SymbolType.None);
}
}
else if (list5item == null)
{
if (setupPropertyInfo(ref list5item, ((CheckBox)sender).Name, MainV2.cs))
{
list5.Clear();
list5curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list5, Color.Yellow, SymbolType.None);
}
}
else if (list6item == null)
{
if (setupPropertyInfo(ref list6item, ((CheckBox)sender).Name, MainV2.cs))
{
list6.Clear();
list6curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list6, Color.Magenta, SymbolType.None);
}
}
else if (list7item == null)
{
if (setupPropertyInfo(ref list7item, ((CheckBox)sender).Name, MainV2.cs))
{
list7.Clear();
list7curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list7, Color.Purple, SymbolType.None);
}
}
else if (list8item == null)
{
if (setupPropertyInfo(ref list8item, ((CheckBox)sender).Name, MainV2.cs))
{
list8.Clear();
list8curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list8, Color.LimeGreen, SymbolType.None);
}
}
else if (list9item == null)
{
if (setupPropertyInfo(ref list9item, ((CheckBox)sender).Name, MainV2.cs))
{
list9.Clear();
list9curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list9, Color.Cyan, SymbolType.None);
}
}
else if (list10item == null)
{
if (setupPropertyInfo(ref list10item, ((CheckBox)sender).Name, MainV2.cs))
{
list10.Clear();
list10curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list10, Color.Violet, SymbolType.None);
}
}
else
{

View File

@ -805,6 +805,8 @@ namespace ArdupilotMega.GCSViews
catch { cmd = option; }
//Console.WriteLine("editformat " + option + " value " + cmd);
ChangeColumnHeader(cmd);
writeKML();
}
catch (Exception ex) { CustomMessageBox.Show(ex.ToString()); }
}
@ -938,6 +940,37 @@ namespace ArdupilotMega.GCSViews
catch (Exception ex) { log.Info(ex.ToString()); }
}
void updateRowNumbers()
{
// number rows
System.Threading.Thread t1 = new System.Threading.Thread(delegate()
{
// thread for updateing row numbers
for (int a = 0; a < Commands.Rows.Count - 0; a++)
{
try
{
if (Commands.Rows[a].HeaderCell.Value == null)
{
Commands.Rows[a].HeaderCell.Style.Alignment = DataGridViewContentAlignment.MiddleCenter;
Commands.Rows[a].HeaderCell.Value = (a + 1).ToString();
}
// skip rows with the correct number
string rowno = Commands.Rows[a].HeaderCell.Value.ToString();
if (!rowno.Equals((a + 1).ToString()))
{
// this code is where the delay is when deleting.
Commands.Rows[a].HeaderCell.Value = (a + 1).ToString();
}
}
catch (Exception) { }
}
});
t1.Name = "Row number updater";
t1.IsBackground = true;
t1.Start();
}
/// <summary>
/// used to write a KML, update the Map view polygon, and update the row headers
/// </summary>
@ -994,33 +1027,7 @@ namespace ArdupilotMega.GCSViews
int usable = 0;
// number rows
System.Threading.Thread t1 = new System.Threading.Thread(delegate()
{
// thread for updateing row numbers
for (int a = 0; a < Commands.Rows.Count - 0; a++)
{
try
{
if (Commands.Rows[a].HeaderCell.Value == null)
{
Commands.Rows[a].HeaderCell.Style.Alignment = DataGridViewContentAlignment.MiddleCenter;
Commands.Rows[a].HeaderCell.Value = (a + 1).ToString();
}
// skip rows with the correct number
string rowno = Commands.Rows[a].HeaderCell.Value.ToString();
if (!rowno.Equals((a + 1).ToString()))
{
// this code is where the delay is when deleting.
Commands.Rows[a].HeaderCell.Value = (a + 1).ToString();
}
}
catch (Exception) { }
}
});
t1.Name = "Row number updater";
t1.IsBackground = true;
t1.Start();
updateRowNumbers();
long temp = System.Diagnostics.Stopwatch.GetTimestamp();
@ -1041,11 +1048,30 @@ namespace ArdupilotMega.GCSViews
if (cell4 == "?" || cell3 == "?")
continue;
if (command == (byte)MAVLink.MAV_CMD.LOITER_TIME || command == (byte)MAVLink.MAV_CMD.LOITER_TURNS || command == (byte)MAVLink.MAV_CMD.LOITER_UNLIM) {
if (command == (byte)MAVLink.MAV_CMD.ROI)
{
pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt,"ROI"+(a+1).ToString()) { color = Color.Red });
GMapMarkerGoogleRed m = new GMapMarkerGoogleRed(new PointLatLng(double.Parse(cell3), double.Parse(cell4)));
m.ToolTipMode = MarkerTooltipMode.Always;
m.ToolTipText = (a + 1).ToString();
m.Tag = (a + 1).ToString();
GMapMarkerRect mBorders = new GMapMarkerRect(m.Position);
{
mBorders.InnerMarker = m;
mBorders.Tag = "Dont draw line";
}
// order matters
objects.Markers.Add(m);
objects.Markers.Add(mBorders);
}
else if (command == (byte)MAVLink.MAV_CMD.LOITER_TIME || command == (byte)MAVLink.MAV_CMD.LOITER_TURNS || command == (byte)MAVLink.MAV_CMD.LOITER_UNLIM)
{
pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt, (a + 1).ToString()){ color = Color.LightBlue });
addpolygonmarker((a + 1).ToString(), double.Parse(cell4), double.Parse(cell3), (int)double.Parse(cell2) , Color.LightBlue);
} else {
}
else
{
pointlist.Add(new PointLatLngAlt(double.Parse(cell3), double.Parse(cell4), (int)double.Parse(cell2) + homealt, (a + 1).ToString()));
addpolygonmarker((a + 1).ToString(), double.Parse(cell4), double.Parse(cell3), (int)double.Parse(cell2) ,null);
}
@ -1896,16 +1922,14 @@ namespace ArdupilotMega.GCSViews
GMapPolygon drawnpolygon;
GMapPolygon gf;
GMapOverlay kmlpolygons;
GMapOverlay geofence;
// layers
GMapOverlay top;
internal GMapOverlay objects;
static GMapOverlay routes;// static so can update from gcs
static GMapOverlay polygons;
public static GMapOverlay objects; // where the markers a drawn
public static GMapOverlay routes;// static so can update from gcs
public static GMapOverlay polygons; // where the track is drawn
GMapOverlay drawnpolygons;
GMapOverlay kmlpolygons;
GMapOverlay geofence;
// etc
readonly Random rnd = new Random();
@ -2071,6 +2095,7 @@ namespace ArdupilotMega.GCSViews
{
try
{
// check if this is a grid point
if (CurentRectMarker.InnerMarker.Tag.ToString().Contains("grid"))
{
drawnpolygon.Points[int.Parse(CurentRectMarker.InnerMarker.Tag.ToString().Replace("grid", "")) - 1] = new PointLatLng(point.Lat, point.Lng);
@ -2082,19 +2107,25 @@ namespace ArdupilotMega.GCSViews
PointLatLng pnew = MainMap.FromLocalToLatLng(e.X, e.Y);
int? pIndex = (int?)CurentRectMarker.Tag;
if (pIndex.HasValue)
// adjust polyline point while we drag
try
{
if (pIndex < polygon.Points.Count)
int? pIndex = (int?)CurentRectMarker.Tag;
if (pIndex.HasValue)
{
polygon.Points[pIndex.Value] = pnew;
lock (thisLock)
if (pIndex < polygon.Points.Count)
{
MainMap.UpdatePolygonLocalPosition(polygon);
polygon.Points[pIndex.Value] = pnew;
lock (thisLock)
{
MainMap.UpdatePolygonLocalPosition(polygon);
}
}
}
}
catch { }
// update rect and marker pos.
if (currentMarker.IsVisible)
{
currentMarker.Position = pnew;
@ -2225,8 +2256,11 @@ namespace ArdupilotMega.GCSViews
{
if (m is GMapMarkerRect)
{
m.Tag = polygonPoints.Count;
polygonPoints.Add(m.Position);
if (m.Tag == null)
{
m.Tag = polygonPoints.Count;
polygonPoints.Add(m.Position);
}
}
}

View File

@ -50,11 +50,8 @@ namespace ArdupilotMega.GCSViews
// gps buffer
int gpsbufferindex = 0;
#if !MAVLINK10
ArdupilotMega.MAVLink.mavlink_gps_raw_t[] gpsbuffer = new MAVLink.mavlink_gps_raw_t[5];
#else
ArdupilotMega.MAVLink.mavlink_gps_raw_int_t[] gpsbuffer = new MAVLink.mavlink_gps_raw_int_t[5];
#endif
sitl_fdm[] sitl_fdmbuffer = new sitl_fdm[5];
// set defaults
int rollgain = 10000;
@ -92,29 +89,21 @@ namespace ArdupilotMega.GCSViews
}
[StructLayout(LayoutKind.Sequential, Pack = 1)]
public struct sitldata
public struct sitl_fdm
{
public double lat;
public double lon;
public double alt;
public double heading;
public double v_north;
public double v_east;
public double ax;
public double ay;
public double az;
public double phidot;
public double thetadot;
public double psidot;
public double phi;
public double theta;
/// <summary>
/// heading
/// </summary>
public double psi;
public double vcas;
public int check;
}
// this is the packet sent by the simulator
// to the APM executable to update the simulator state
// All values are little-endian
public double latitude, longitude; // degrees
public double altitude; // MSL
public double heading; // degrees
public double speedN, speedE; // m/s
public double xAccel, yAccel, zAccel; // m/s/s in body frame
public double rollRate, pitchRate, yawRate; // degrees/s/s in earth frame
public double rollDeg, pitchDeg, yawDeg; // euler angles, degrees
public double airspeed; // m/s
public UInt32 magic; // 0x4c56414e
};
const int AEROSIMRC_MAX_CHANNELS = 39;
@ -633,6 +622,7 @@ namespace ArdupilotMega.GCSViews
if (comPort.BaseStream.IsOpen == false) { break; }
try
{
MainV2.cs.UpdateCurrentSettings(null); // when true this uses alot more cpu time
if ((DateTime.Now - simsendtime).TotalMilliseconds > 19)
@ -715,13 +705,9 @@ namespace ArdupilotMega.GCSViews
MavLink = new UdpClient("127.0.0.1", 14550);
}
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();
#endif
ArdupilotMega.MAVLink.mavlink_attitude_t oldatt = new ArdupilotMega.MAVLink.mavlink_attitude_t();
sitl_fdm oldgps = new sitl_fdm();
/// <summary>
/// Recevied UDP packet, process and send required data to serial port.
@ -731,19 +717,7 @@ namespace ArdupilotMega.GCSViews
/// <param name="comPort">Com Port</param>
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_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();
#endif
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_vfr_hud_t asp = new ArdupilotMega.MAVLink.mavlink_vfr_hud_t();
sitl_fdm sitldata = new sitl_fdm();
if (data[0] == 'D' && data[1] == 'A')
{
@ -774,114 +748,55 @@ namespace ArdupilotMega.GCSViews
if (xplane9)
{
att.pitch = (DATA[18][0] * deg2rad);
att.roll = (DATA[18][1] * deg2rad);
att.yaw = (DATA[18][2] * deg2rad);
att.pitchspeed = (DATA[17][0]);
att.rollspeed = (DATA[17][1]);
att.yawspeed = (DATA[17][2]);
sitldata.pitchDeg = (DATA[18][0]);
sitldata.rollDeg = (DATA[18][1]);
sitldata.yawDeg = (DATA[18][2]);
sitldata.pitchRate = (DATA[17][0] * rad2deg);
sitldata.rollRate = (DATA[17][1] * rad2deg);
sitldata.yawRate = (DATA[17][2] * rad2deg);
sitldata.heading = ((float)DATA[19][2]);
}
else
{
att.pitch = (DATA[17][0] * deg2rad);
att.roll = (DATA[17][1] * deg2rad);
att.yaw = (DATA[17][2] * deg2rad);
att.pitchspeed = (DATA[16][0]);
att.rollspeed = (DATA[16][1]);
att.yawspeed = (DATA[16][2]);
sitldata.pitchDeg = (DATA[17][0]);
sitldata.rollDeg = (DATA[17][1]);
sitldata.yawDeg = (DATA[17][2]);
sitldata.pitchRate = (DATA[16][0] * rad2deg);
sitldata.rollRate = (DATA[16][1] * rad2deg);
sitldata.yawRate = (DATA[16][2] * rad2deg);
sitldata.heading = (DATA[18][2]);
}
TimeSpan timediff = DateTime.Now - oldtime;
sitldata.airspeed = ((DATA[3][5] * .44704));
float pdiff = (float)((att.pitch - oldatt.pitch) / timediff.TotalSeconds);
float rdiff = (float)((att.roll - oldatt.roll) / timediff.TotalSeconds);
float ydiff = (float)((att.yaw - oldatt.yaw) / timediff.TotalSeconds);
sitldata.latitude = (DATA[20][0]);
sitldata.longitude = (DATA[20][1]);
sitldata.altitude = (DATA[20][2] * ft2m);
// Console.WriteLine("{0:0.00000} {1:0.00000} {2:0.00000} \t {3:0.00000} {4:0.00000} {5:0.00000}", pdiff, rdiff, ydiff, DATA[17][0], DATA[17][1], DATA[17][2]);
sitldata.speedN = DATA[21][3];// (DATA[3][7] * 0.44704 * Math.Sin(sitldata.heading * deg2rad));
sitldata.speedE = -DATA[21][5];// (DATA[3][7] * 0.44704 * Math.Cos(sitldata.heading * deg2rad));
oldatt = att;
// YLScsDrawing.Drawing3d.Vector3d accel3D = HIL.QuadCopter.RPY_to_XYZ(DATA[18][1], DATA[18][0], 0, -9.8); //DATA[18][2]
Int16 xgyro = Constrain(att.rollspeed * 1000.0, Int16.MinValue, Int16.MaxValue);
Int16 ygyro = Constrain(att.pitchspeed * 1000.0, Int16.MinValue, Int16.MaxValue);
Int16 zgyro = Constrain(att.yawspeed * 1000.0, Int16.MinValue, Int16.MaxValue);
// float turnrad = (float)(((DATA[3][7] * 0.44704) * (DATA[3][7] * 0.44704) * 1.943844) / (float)(11.26 * Math.Tan(sitldata.rollDeg * deg2rad))) * ft2m;
oldtime = DateTime.Now;
// float centripaccel = (float)((DATA[3][7] * 0.44704) * (DATA[3][7] * 0.44704)) / turnrad;
YLScsDrawing.Drawing3d.Vector3d accel3D = HIL.QuadCopter.RPY_to_XYZ(DATA[18][1], DATA[18][0], 0, -9.8); //DATA[18][2]
// YLScsDrawing.Drawing3d.Vector3d cent3D = HIL.QuadCopter.RPY_to_XYZ(DATA[18][1] - 90, 0, 0, centripaccel);
float turnrad = (float)(((DATA[3][7] * 0.44704) * (DATA[3][7] * 0.44704) * 1.943844) / (float)(11.26 * Math.Tan(att.roll))) * ft2m;
float centripaccel = (float)((DATA[3][7] * 0.44704) * (DATA[3][7] * 0.44704)) / turnrad;
//Console.WriteLine("old {0} {1} {2}",accel3D.X,accel3D.Y,accel3D.Z);
YLScsDrawing.Drawing3d.Vector3d cent3D = HIL.QuadCopter.RPY_to_XYZ(DATA[18][1] - 90, 0, 0, centripaccel);
accel3D -= cent3D;
//Console.WriteLine("new {0} {1} {2}", accel3D.X, accel3D.Y, accel3D.Z);
oldax = DATA[4][5];
olday = DATA[4][6];
oldaz = DATA[4][4];
double head = DATA[18][2] - 90;
#if MAVLINK10
imu.time_usec = ((ulong)DateTime.Now.ToBinary());
#else
imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif
imu.xgyro = xgyro; // roll - yes
imu.xmag = (short)(Math.Sin(head * deg2rad) * 1000);
imu.ygyro = ygyro; // pitch - yes
imu.ymag = (short)(Math.Cos(head * deg2rad) * 1000);
imu.zgyro = zgyro;
imu.zmag = 0;
imu.xacc = (Int16)(accel3D.X * 1000); // pitch
imu.yacc = (Int16)(accel3D.Y * 1000); // roll
imu.zacc = (Int16)(accel3D.Z * 1000);
//Console.WriteLine("ax " + imu.xacc + " ay " + imu.yacc + " az " + imu.zacc);
#if MAVLINK10
gps.alt = (int)(DATA[20][2] * ft2m * 1000);
gps.fix_type = 3;
if (xplane9)
{
gps.cog = (ushort)((float)DATA[19][2]);
}
else
{
gps.cog = (ushort)((float)DATA[18][2]);
}
gps.lat = (int)(DATA[20][0] * 1.0e7);
gps.lon = (int)(DATA[20][1] * 1.0e7);
gps.time_usec = ((ulong)0);
gps.vel = (ushort)(DATA[3][7] * 0.44704 * 100);
#else
gps.alt = ((float)(DATA[20][2] * ft2m));
gps.fix_type = 3;
if (xplane9)
{
gps.hdg = ((float)DATA[19][2]);
}
else
{
gps.hdg = ((float)DATA[18][2]);
}
gps.lat = ((float)DATA[20][0]);
gps.lon = ((float)DATA[20][1]);
gps.usec = ((ulong)0);
gps.v = ((float)(DATA[3][7] * 0.44704));
#endif
asp.airspeed = ((float)(DATA[3][5] * .0044704));
// accel3D -= cent3D;
// sitldata.xAccel = accel3D.X;
// sitldata.yAccel = accel3D.Y;
// sitldata.zAccel = accel3D.Z;
}
else if (receviedbytes == 0x64) // FG binary udp
{
//FlightGear
/*
fgIMUData imudata2 = data.ByteArrayToStructureBigEndian<fgIMUData>(0);
@ -930,196 +845,75 @@ namespace ArdupilotMega.GCSViews
//FileStream stream = File.OpenWrite("fgdata.txt");
//stream.Write(data, 0, receviedbytes);
//stream.Close();
*/
}
else if (receviedbytes == 662 || receviedbytes == 658) // 658 = 3.83 662 = 3.91
{
aeroin = data.ByteArrayToStructure<TDataFromAeroSimRC>(0);
att.pitch = (aeroin.Model_fPitch);
att.roll = (aeroin.Model_fRoll * -1);
att.yaw = (float)((aeroin.Model_fHeading));
sitldata.pitchDeg = (aeroin.Model_fPitch * rad2deg);
sitldata.rollDeg = (aeroin.Model_fRoll * -1 * rad2deg);
sitldata.yawDeg = ((aeroin.Model_fHeading * rad2deg));
//Console.WriteLine("degs r {0:0.000} p {1:0.000} y {2:0.000} rates {3:0.000} {4:0.000} {5:0.000}", att.roll * -rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelZ * rad2deg);
sitldata.pitchRate = aeroin.Model_fAngVel_Body_X * rad2deg;
sitldata.rollRate = aeroin.Model_fAngVel_Body_Y * rad2deg;
sitldata.yawRate = -aeroin.Model_fAngVel_Body_Z * rad2deg;
//Console.WriteLine("mine2 {0} {1} {2} ", answer.Item1 , answer.Item2 , answer.Item3 );
sitldata.xAccel = aeroin.Model_fAccel_Body_X; // pitch
sitldata.yAccel = aeroin.Model_fAccel_Body_Y; // roll
sitldata.zAccel = aeroin.Model_fAccel_Body_Z;
//StreamWriter SW = new StreamWriter("aerosim.txt",true);
//SW.WriteLine(aeroin.Model_fRoll + "," + aeroin.Model_fPitch + "," + aeroin.Model_fHeading + "," + aeroin.Model_fAngVelX + "," + aeroin.Model_fAngVelY + "," + aeroin.Model_fAngVelZ);
//SW.Close();
att.pitchspeed = (float)aeroin.Model_fAngVel_Body_X;
att.rollspeed = (float)aeroin.Model_fAngVel_Body_Y;
att.yawspeed = (float)-aeroin.Model_fAngVel_Body_Z;
// YLScsDrawing.Drawing3d.Vector3d accel3D = HIL.QuadCopter.RPY_to_XYZ(att.roll, att.pitch, 0, -9.8); //DATA[18][2]
#if MAVLINK10
imu.time_usec = ((ulong)DateTime.Now.ToBinary());
#else
imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif
imu.xgyro = (short)(aeroin.Model_fAngVel_Body_X * 1000); // roll - yes
//imu.xmag = (short)(Math.Sin(head * deg2rad) * 1000);
imu.ygyro = (short)(aeroin.Model_fAngVel_Body_Y * 1000); // pitch - yes
//imu.ymag = (short)(Math.Cos(head * deg2rad) * 1000);
imu.zgyro = (short)(aeroin.Model_fAngVel_Body_Z * 1000);
//imu.zmag = 0;
sitldata.altitude = aeroin.Model_fPosZ;
sitldata.latitude = aeroin.Model_fLatitude;
sitldata.longitude = aeroin.Model_fLongitude;
YLScsDrawing.Drawing3d.Vector3d accel3D = HIL.QuadCopter.RPY_to_XYZ(att.roll, att.pitch, 0, -9.8); //DATA[18][2]
sitldata.speedN = aeroin.Model_fVelX;
sitldata.speedE = aeroin.Model_fVelY;
imu.xacc = (Int16)((accel3D.X + aeroin.Model_fAccel_Body_X) * 1000); // pitch
imu.yacc = (Int16)((accel3D.Y + aeroin.Model_fAccel_Body_Y) * 1000); // roll
imu.zacc = (Int16)((accel3D.Z + aeroin.Model_fAccel_Body_Z) * 1000);
// Console.WriteLine("x {0} y {1} z {2}", imu.xacc, imu.yacc, imu.zacc);
#if MAVLINK10
gps.alt = ((int)(aeroin.Model_fPosZ) * 1000);
gps.fix_type = 3;
gps.cog = (ushort)(Math.Atan2(aeroin.Model_fVelX, aeroin.Model_fVelY) * rad2deg * 100);
gps.lat = (int)(aeroin.Model_fLatitude * 1.0e7);
gps.lon = (int)(aeroin.Model_fLongitude * 1.0e7);
gps.time_usec = ((ulong)DateTime.Now.Ticks);
gps.vel = (ushort)(Math.Sqrt((aeroin.Model_fVelY * aeroin.Model_fVelY) + (aeroin.Model_fVelX * aeroin.Model_fVelX)) * 100);
#else
gps.alt = ((float)(aeroin.Model_fPosZ));
gps.fix_type = 3;
gps.hdg = ((float)Math.Atan2(aeroin.Model_fVelX, aeroin.Model_fVelY) * rad2deg);
gps.lat = ((float)aeroin.Model_fLatitude);
gps.lon = ((float)aeroin.Model_fLongitude);
gps.usec = ((ulong)DateTime.Now.Ticks);
gps.v = ((float)Math.Sqrt((aeroin.Model_fVelY * aeroin.Model_fVelY) + (aeroin.Model_fVelX * aeroin.Model_fVelX)));
#endif
float xvec = aeroin.Model_fVelY - aeroin.Model_fWindVelY;
float yvec = aeroin.Model_fVelX - aeroin.Model_fWindVelX;
asp.airspeed = ((float)Math.Sqrt((yvec * yvec) + (xvec * xvec)));
sitldata.airspeed = ((float)Math.Sqrt((yvec * yvec) + (xvec * xvec)));
}
else if (receviedbytes == 408)
{
FGNetFDM fdm = data.ByteArrayToStructureBigEndian<FGNetFDM>(0);
lastfdmdata = fdm;
att.roll = fdm.phi;
att.pitch = fdm.theta;
att.yaw = fdm.psi;
#if MAVLINK10
imu.time_usec = ((ulong)DateTime.Now.ToBinary());
#else
imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif
imu.xgyro = (short)(fdm.phidot * 1000); // roll - yes
//imu.xmag = (short)(Math.Sin(head * deg2rad) * 1000);
imu.ygyro = (short)(fdm.thetadot * 1000); // pitch - yes
//imu.ymag = (short)(Math.Cos(head * deg2rad) * 1000);
imu.zgyro = (short)(fdm.psidot * 1000);
imu.zmag = 0;
sitldata.rollDeg = fdm.phi * rad2deg;
sitldata.pitchDeg = fdm.theta * rad2deg;
sitldata.yawDeg = fdm.psi * rad2deg;
imu.xacc = (Int16)Math.Min(Int16.MaxValue, Math.Max(Int16.MinValue, (fdm.A_X_pilot * 9808 / 32.2))); // pitch
imu.yacc = (Int16)Math.Min(Int16.MaxValue, Math.Max(Int16.MinValue, (fdm.A_Y_pilot * 9808 / 32.2))); // roll
imu.zacc = (Int16)Math.Min(Int16.MaxValue, Math.Max(Int16.MinValue, (fdm.A_Z_pilot / 32.2 * 9808)));
//Console.WriteLine("ax " + imu.xacc + " ay " + imu.yacc + " az " + imu.zacc);
#if MAVLINK10
gps.alt = ((int)(fdm.altitude * 1000));
gps.fix_type = 3;
gps.cog = (ushort)((((Math.Atan2(fdm.v_east, fdm.v_north) * rad2deg) + 360) % 360) * 100);
gps.lat = (int)(fdm.latitude * rad2deg * 1.0e7);
gps.lon = (int)(fdm.longitude * rad2deg * 1.0e7);
gps.time_usec = ((ulong)DateTime.Now.Ticks);
gps.vel = (ushort)(Math.Sqrt((fdm.v_north * fdm.v_north) + (fdm.v_east * fdm.v_east)) * ft2m * 100);
#else
gps.alt = ((float)(fdm.altitude));
gps.fix_type = 3;
gps.hdg = (float)(((Math.Atan2(fdm.v_east, fdm.v_north) * rad2deg) + 360) % 360);
//Console.WriteLine(gps.hdg);
gps.lat = ((float)fdm.latitude * rad2deg);
gps.lon = ((float)fdm.longitude * rad2deg);
gps.usec = ((ulong)DateTime.Now.Ticks);
gps.v = ((float)Math.Sqrt((fdm.v_north * fdm.v_north) + (fdm.v_east * fdm.v_east)) * ft2m);
sitldata.rollRate = fdm.phidot * rad2deg;
sitldata.pitchRate = fdm.thetadot * rad2deg;
sitldata.yawRate = fdm.psidot * rad2deg;
#endif
asp.airspeed = fdm.vcas * 0.5144444f;// knots to m/s
sitldata.xAccel = (fdm.A_X_pilot * 9.808 / 32.2); // pitch
sitldata.yAccel = (fdm.A_Y_pilot * 9.808 / 32.2); // roll
sitldata.zAccel = (fdm.A_Z_pilot / 32.2 * 9.808);
sitldata.altitude = (fdm.altitude);
sitldata.latitude = (fdm.latitude * rad2deg);
sitldata.longitude = (fdm.longitude * rad2deg);
sitldata.speedN = fdm.v_east * ft2m;
sitldata.speedE = fdm.v_north * ft2m;
sitldata.airspeed = fdm.vcas * 0.5144444f;// knots to m/s
}
else
{
//FlightGear - old style udp
DATA[20] = new float[8];
DATA[18] = new float[8];
DATA[19] = new float[8];
DATA[3] = new float[8];
// this text line is defined from ardupilot.xml
string telem = Encoding.ASCII.GetString(data, 0, data.Length);
try
{
// should convert this to regex.... or just leave it.
int oldpos = 0;
int pos = telem.IndexOf(",");
DATA[20][0] = float.Parse(telem.Substring(oldpos, pos - 1), new System.Globalization.CultureInfo("en-US"));
oldpos = pos;
pos = telem.IndexOf(",", pos + 1);
DATA[20][1] = float.Parse(telem.Substring(oldpos + 1, pos - 1 - oldpos), new System.Globalization.CultureInfo("en-US"));
oldpos = pos;
pos = telem.IndexOf(",", pos + 1);
DATA[20][2] = float.Parse(telem.Substring(oldpos + 1, pos - 1 - oldpos), new System.Globalization.CultureInfo("en-US"));
oldpos = pos;
pos = telem.IndexOf(",", pos + 1);
DATA[18][1] = float.Parse(telem.Substring(oldpos + 1, pos - 1 - oldpos), new System.Globalization.CultureInfo("en-US"));
oldpos = pos;
pos = telem.IndexOf(",", pos + 1);
DATA[18][0] = float.Parse(telem.Substring(oldpos + 1, pos - 1 - oldpos), new System.Globalization.CultureInfo("en-US"));
oldpos = pos;
pos = telem.IndexOf(",", pos + 1);
DATA[19][2] = float.Parse(telem.Substring(oldpos + 1, pos - 1 - oldpos), new System.Globalization.CultureInfo("en-US"));
oldpos = pos;
pos = telem.IndexOf("\n", pos + 1);
DATA[3][6] = float.Parse(telem.Substring(oldpos + 1, pos - 1 - oldpos), new System.Globalization.CultureInfo("en-US"));
DATA[3][7] = DATA[3][6];
}
catch (Exception) { }
chkSensor.Checked = false;
att.pitch = (DATA[18][0]);
att.roll = (DATA[18][1]);
att.yaw = (DATA[19][2]);
#if MAVLINK10
gps.alt = ((int)(DATA[20][2] * ft2m * 1000));
gps.fix_type = 3;
gps.cog = (ushort)(DATA[18][2] * 100);
gps.lat = (int)(DATA[20][0] * 1.0e7);
gps.lon = (int)(DATA[20][1] * 1.0e7);
gps.time_usec = ((ulong)0);
gps.vel = (ushort)((DATA[3][7] * 0.44704 * 100));
#else
gps.alt = ((float)(DATA[20][2] * ft2m));
gps.fix_type = 3;
gps.hdg = ((float)DATA[18][2]);
gps.lat = ((float)DATA[20][0]);
gps.lon = ((float)DATA[20][1]);
gps.usec = ((ulong)0);
gps.v = ((float)(DATA[3][7] * 0.44704));
#endif
asp.airspeed = ((float)(DATA[3][6] * 0.44704));
log.Info("Bad Udp Packet " + receviedbytes);
return;
}
// write arduimu to ardupilot
@ -1168,54 +962,15 @@ namespace ArdupilotMega.GCSViews
if (RAD_softXplanes.Checked && chkSensor.Checked)
{
sitldata sitlout = new sitldata();
sitldata.magic = (int)0x4c56414e;
ArdupilotMega.HIL.Utils.FLIGHTtoBCBF(ref att.pitchspeed, ref att.rollspeed, ref att.yawspeed, DATA[19][0] * deg2rad, DATA[19][1] * deg2rad);
//Console.WriteLine("{0:0.00000} {1:0.00000} {2:0.00000} \t {3:0.00000} {4:0.00000} {5:0.00000}", att.pitchspeed, att.rollspeed, att.yawspeed, DATA[17][0], DATA[17][1], DATA[17][2]);
Tuple<double, double, double> ans = ArdupilotMega.HIL.Utils.OGLtoBCBF(att.pitch, att.roll, att.yaw, 0, 0, 9.8);
//Console.WriteLine("acc {0:0.00000} {1:0.00000} {2:0.00000} \t {3:0.00000} {4:0.00000} {5:0.00000}", ans.Item1, ans.Item2, ans.Item3, accel3D.X, accel3D.Y, accel3D.Z);
sitlout.alt = gps.alt;
sitlout.lat = gps.lat;
sitlout.lon = gps.lon;
#if !MAVLINK10
sitlout.heading = gps.hdg;
#else
sitlout.heading = gps.cog;
#endif
sitlout.v_north = DATA[21][4];
sitlout.v_east = DATA[21][5];
// correct accel
sitlout.ax = -ans.Item2; // pitch
sitlout.ay = -ans.Item1; // roll
sitlout.az = ans.Item3; // yaw
sitlout.phidot = -0.5;// att.pitchspeed;
// sitlout.thetadot = att.rollspeed;
//sitlout.psidot = att.yawspeed;
sitlout.phi = att.roll * rad2deg;
sitlout.theta = att.pitch * rad2deg;
sitlout.psi = att.yaw * rad2deg;
sitlout.vcas = asp.airspeed;
sitlout.check = (int)0x4c56414e;
byte[] sendme = StructureToByteArray(sitlout);
byte[] sendme = StructureToByteArray(sitldata);
SITLSEND.Send(sendme, sendme.Length);
return;
}
#if MAVLINK10
TimeSpan gpsspan = DateTime.Now - lastgpsupdate;
// add gps delay
@ -1224,12 +979,12 @@ namespace ArdupilotMega.GCSViews
lastgpsupdate = DateTime.Now;
// save current fix = 3
gpsbuffer[gpsbufferindex % gpsbuffer.Length] = gps;
sitl_fdmbuffer[gpsbufferindex % sitl_fdmbuffer.Length] = sitldata;
// Console.WriteLine((gpsbufferindex % gpsbuffer.Length) + " " + ((gpsbufferindex + (gpsbuffer.Length - 1)) % gpsbuffer.Length));
// return buffer index + 5 = (3 + 5) = 8 % 6 = 2
oldgps = gpsbuffer[(gpsbufferindex + (gpsbuffer.Length - 1)) % gpsbuffer.Length];
oldgps = sitl_fdmbuffer[(gpsbufferindex + (sitl_fdmbuffer.Length - 1)) % sitl_fdmbuffer.Length];
//comPort.sendPacket(oldgps);
@ -1237,72 +992,42 @@ namespace ArdupilotMega.GCSViews
}
hilstate.alt = oldgps.alt;
hilstate.lat = oldgps.lat;
hilstate.lon = oldgps.lon;
hilstate.pitch = att.pitch;
hilstate.pitchspeed = att.pitchspeed;
hilstate.roll = att.roll;
hilstate.rollspeed = att.rollspeed;
hilstate.time_usec = gps.time_usec;
hilstate.vx = (short)(gps.vel * Math.Sin(gps.cog * deg2rad));
hilstate.vy = (short)(gps.vel * Math.Cos(gps.cog * deg2rad));
hilstate.vz = 0;
hilstate.xacc = imu.xacc;
hilstate.yacc = imu.yacc;
hilstate.yaw = att.yaw;
hilstate.yawspeed = att.yawspeed;
hilstate.zacc = imu.zacc;
MAVLink.mavlink_hil_state_t hilstate = new MAVLink.mavlink_hil_state_t();
hilstate.time_usec = (UInt64)DateTime.Now.Ticks; // microsec
hilstate.lat = (int)(oldgps.latitude * 1e7); // * 1E7
hilstate.lon = (int)(oldgps.longitude * 1e7); // * 1E7
hilstate.alt = (int)(oldgps.altitude * 1000); // mm
// Console.WriteLine(hilstate.alt);
hilstate.pitch = (float)sitldata.pitchDeg * deg2rad; // (rad)
hilstate.pitchspeed = (float)sitldata.pitchRate * rad2deg; // (rad/s)
hilstate.roll = (float)sitldata.rollDeg * deg2rad; // (rad)
hilstate.rollspeed = (float)sitldata.rollRate * deg2rad; // (rad/s)
hilstate.yaw = (float)sitldata.yawDeg * deg2rad; // (rad)
hilstate.yawspeed = (float)sitldata.yawRate * deg2rad; // (rad/s)
hilstate.vx = (short)(sitldata.speedN * 100); // m/s * 100
hilstate.vy = (short)(sitldata.speedE * 100); // m/s * 100
hilstate.vz = 0; // m/s * 100
hilstate.xacc = (short)(sitldata.xAccel * 1000); // (mg)
hilstate.yacc = (short)(sitldata.yAccel * 1000); // (mg)
hilstate.zacc = (short)(sitldata.zAccel * 1000); // (mg)
comPort.sendPacket(hilstate);
// comPort.sendPacket(oldgps);
comPort.sendPacket(asp);
#else
if (chkSensor.Checked == false) // attitude
{
comPort.sendPacket(att);
comPort.sendPacket(asp);
}
else // raw imu
{
// imudata
comPort.sendPacket(imu);
#endif
comPort.sendPacket(new MAVLink.mavlink_vfr_hud_t() { airspeed = (float)sitldata.airspeed } );
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
double calc = (101325 * Math.Pow(1 - 2.25577 * Math.Pow(10, -5) * sitldata.altitude, 5.25588)); // updated from valid gps
pres.press_diff1 = (short)(int)(calc - 101325); // 0 alt is 0 pa
comPort.sendPacket(pres);
#if !MAVLINK10
comPort.sendPacket(asp);
}
TimeSpan gpsspan = DateTime.Now - lastgpsupdate;
// add gps delay
if (gpsspan.TotalMilliseconds >= GPS_rate)
{
lastgpsupdate = DateTime.Now;
// 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]);
gpsbufferindex++;
}
#endif
// comPort.sendPacket(pres);
}
HIL.QuadCopter quad = new HIL.QuadCopter();
@ -1395,9 +1120,9 @@ namespace ArdupilotMega.GCSViews
Array.Copy(BitConverter.GetBytes((double)(quad.longitude)), 0, FlightGear, 40, 8);
Array.Copy(BitConverter.GetBytes((double)(quad.altitude * 1 / ft2m)), 0, FlightGear, 48, 8);
Array.Copy(BitConverter.GetBytes((double)((quad.altitude - quad.ground_level) * 1 / ft2m)), 0, FlightGear, 56, 8);
Array.Copy(BitConverter.GetBytes((double)(quad.roll)), 0, FlightGear, 64, 8);
Array.Copy(BitConverter.GetBytes((double)(quad.pitch)), 0, FlightGear, 72, 8);
Array.Copy(BitConverter.GetBytes((double)(quad.yaw)), 0, FlightGear, 80, 8);
Array.Copy(BitConverter.GetBytes((double)(quad.roll * rad2deg)), 0, FlightGear, 64, 8);
Array.Copy(BitConverter.GetBytes((double)(quad.pitch * rad2deg)), 0, FlightGear, 72, 8);
Array.Copy(BitConverter.GetBytes((double)(quad.yaw * rad2deg)), 0, FlightGear, 80, 8);
if (RAD_softFlightGear.Checked || RAD_softXplanes.Checked)
{

View File

@ -19,72 +19,77 @@ namespace ArdupilotMega.HIL
public double longitude = 0;
public double altitude = 0;
public double pitch = 0.0; //# degrees
public double roll = 0.0; //# degrees
public double yaw = 0.0; //# degrees
public Matrix3 dcm = new Matrix3();
public double pitch_rate = 0.0; //# degrees/s
public double roll_rate = 0.0; //# degrees/s
public double yaw_rate = 0.0; //# degrees/s
public Vector3 gyro = new Vector3(0, 0, 0);
public double pDeg = 0.0; // degrees/s
public double qDeg = 0.0; // degrees/s
public double rDeg = 0.0; // degrees/s
public Vector3 accel_body = new Vector3(0, 0, 0);
public Vector3d velocity = new Vector3d(0, 0, 0); //# m/s, North, East, Up
public Vector3d position = new Vector3d(0, 0, 0); //# m North, East, Up
public Vector3d accel = new Vector3d(0, 0, 0); //# m/s/s North, East, Up
public Vector3 velocity = new Vector3(0, 0, 0); //# m/s, North, East, Up
public Vector3 position = new Vector3(0, 0, 0); //# m North, East, Up
public Vector3 accel = new Vector3(0, 0, 0); //# m/s/s North, East, Up
public double mass = 0.0;
public double update_frequency = 50;//# in Hz
public double gravity = 9.8;//# m/s/s
public Vector3d accelerometer = new Vector3d(0, 0, -9.8);
public double gravity = 9.80665;//# m/s/s
public Vector3 accelerometer = new Vector3(0, 0, -9.80665);
public double roll = 0;
public double pitch = 0;
public double yaw = 0;
public Aircraft()
{
self = this;
}
public void normalise()
public bool on_ground(Vector3 position = null)
{
roll = norm(roll, -180, 180);
pitch = norm(pitch, -180, 180);
yaw = norm(yaw, 0, 360);
// '''return true if we are on the ground'''
if (position == null)
position = self.position;
return (-position.z) + self.home_altitude <= self.ground_level + self.frame_height;
}
double norm(double angle, double min, double max)
{
while (angle > max)
angle -= 360;
while (angle < min)
angle += 360;
return angle;
}
public void update_position()
public void update_position(double delta_time = 0)
{
//'''update lat/lon/alt from position'''
double radius_of_earth = 6378100.0;// # in meters
double dlat = rad2deg * (Math.Atan(position.X / radius_of_earth));
double dlon = rad2deg * (Math.Atan(position.Y / radius_of_earth));
double bearing = degrees(atan2(self.position.y, self.position.x));
double distance = sqrt(self.position.x * self.position.x + self.position.y * self.position.y);
altitude = home_altitude + position.Z;
latitude = home_latitude + dlat;
longitude = home_longitude + dlon;
gps_newpos(self.home_latitude, self.home_longitude,
bearing, distance);
// work out what the accelerometer would see
double xAccel = sin(radians(self.pitch)) * cos(radians(self.roll));
double yAccel = -sin(radians(self.roll)) * cos(radians(self.pitch));
double zAccel = -cos(radians(self.roll)) * cos(radians(self.pitch));
double scale = 9.81 / sqrt((xAccel * xAccel) + (yAccel * yAccel) + (zAccel * zAccel));
xAccel *= scale;
yAccel *= scale;
zAccel *= scale;
self.accelerometer = new Vector3d(xAccel, yAccel, zAccel);
self.altitude = self.home_altitude - self.position.z;
Vector3 velocity_body = self.dcm.transposed() * self.velocity;
self.accelerometer = self.accel_body.copy();
}
public void gps_newpos(double lat, double lon, double bearing, double distance)
{
// '''extrapolate latitude/longitude given a heading and distance
// thanks to http://www.movable-type.co.uk/scripts/latlong.html
// '''
// from math import sin, asin, cos, atan2, radians, degrees
double radius_of_earth = 6378100.0;//# in meters
double lat1 = radians(lat);
double lon1 = radians(lon);
double brng = radians(bearing);
double dr = distance / radius_of_earth;
double lat2 = asin(sin(lat1) * cos(dr) +
cos(lat1) * sin(dr) * cos(brng));
double lon2 = lon1 + atan2(sin(brng) * sin(dr) * cos(lat1),
cos(dr) - sin(lat1) * sin(lat2));
latitude = degrees(lat2);
longitude = degrees(lon2);
//return (degrees(lat2), degrees(lon2));
}
}
}

View File

@ -0,0 +1,364 @@
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using Sharp3D.Math.Core;
namespace ArdupilotMega.HIL
{
class FlashQuad
{
public ahrsc ahrs = new ahrsc() ;// :AHRS;
public Vector3D loc = new Vector3D() ;// :Location;
public param g = new param() ;// :Parameters;
//public var apm_rc :APM_RC;
//public var motor_filter_0 :AverageFilter;
//public var motor_filter_1 :AverageFilter;
//public var motor_filter_2 :AverageFilter;
//public var motor_filter_3 :AverageFilter;
public Vector3D drag = new Vector3D();// :Vector3D; //
public Vector3D airspeed = new Vector3D();// :Vector3D; //
//public var thrust :Vector3D; //
public Vector3D position = new Vector3D();// :Vector3D; //
public Vector3D velocity = new Vector3D();// :Vector3D;
//public var velocity_old :Vector3D;
//public var wind :Point; //
public Vector3D rot_accel = new Vector3D();// :Vector3D; //
public Vector3D angle3D = new Vector3D();// :Vector3D; //
//public var windGenerator :Wind; //
public double gravity = 980.5;
public double thrust_scale = 0.4;
public double throttle = 500;
public double rotation_bias = 1;
private double _jump_z = 0;
private Vector3D v3 = new Vector3D();
public class ahrsc
{
public Matrix3D dcm = new Matrix3D(Matrix3D.Identity);
public Vector3D gyro = new Vector3D();
public Vector3D omega = new Vector3D();
public Vector3D accel = new Vector3D();
public Vector3D rotation_speed = new Vector3D();
public double roll_sensor;
public double pitch_sensor;
public double yaw_sensor;
}
public class param
{
// ---------------------------------------------
// Sim Details controls
// ---------------------------------------------
public int sim_iterations = 99999;
public int sim_speed = 1;
public double windSpeedMin = 150;
public double windSpeedMax = 200;
public double windPeriod = 30000;
public double windDir = 45;
public double airDensity = 1.184;
//public var crossSection :Number = 0.015;
public double crossSection = 0.012;
public double dragCE = 0.20;
public double speed_filter_size = 2;
public double motor_kv = 1000;
public double moment = 3;
public double mass = 500;
public int esc_delay = 12;
// -----------------------------------------
// Inertial control
// -----------------------------------------
public double speed_correction_z = 0.0350;
public double xy_speed_correction = 0.030;
public double xy_offset_correction = 0.00001;
public double xy_pos_correction = 0.08;
public double z_offset_correction = 0.00004;
public double z_pos_correction = 0.2;
public double accel_bias_x = .9;
public double accel_bias_z = .9;
public double accel_bias_y = .9;
}
double scale_rc(int sn, float servo, float min, float max)
{
float min_pwm = 1000;
float max_pwm = 2000;
//'''scale a PWM value''' # default to servo range of 1000 to 2000
if (MainV2.comPort.param.Count > 0)
{
min_pwm = int.Parse(MainV2.comPort.param["RC3_MIN"].ToString());
max_pwm = int.Parse(MainV2.comPort.param["RC3_MAX"].ToString());
}
float p = (servo - min_pwm) / (max_pwm - min_pwm);
float v = min + p * (max - min);
if (v < min)
v = min;
if (v > max)
v = max;
return v * 1000;
}
public void update(ref double[] motor_output, double dt)
{
var _thrust = 0.0;
rot_accel = new Vector3D(0,0,0);
angle3D.X = angle3D.Y = 0;
angle3D.Z = 1;
// wind = windGenerator.read();
// ESC's moving average filter
// var motor_output:Array = new Array(4);
// motor_output[0] = motor_filter_0.apply(apm_rc.get_motor_output(0));
// motor_output[1] = motor_filter_1.apply(apm_rc.get_motor_output(1));
// motor_output[2] = motor_filter_2.apply(apm_rc.get_motor_output(2));
// motor_output[3] = motor_filter_3.apply(apm_rc.get_motor_output(3));
for (int i = 0; i < motor_output.Length; i++)
{
if (motor_output[i] <= 0.0)
{
motor_output[i] = 0;
}
else
{
motor_output[i] = scale_rc(i, (float)motor_output[i], 0.0f, 1.0f);
//servos[i] = motor_speed[i];
}
}
/*
2
1 0
3
*/
// setup motor rotations
rot_accel.X -= g.motor_kv * motor_output[0]; // roll
rot_accel.X += g.motor_kv * motor_output[1];
rot_accel.Y -= g.motor_kv * motor_output[3];
rot_accel.Y += g.motor_kv * motor_output[2];
rot_accel.Z += g.motor_kv * motor_output[0] * .08; // YAW
rot_accel.Z += g.motor_kv * motor_output[1] * .08;
rot_accel.Z -= g.motor_kv * motor_output[2] * .08;
rot_accel.Z -= g.motor_kv * motor_output[3] * .08;
rot_accel.X /= g.moment;
rot_accel.Y /= g.moment;
rot_accel.Z /= g.moment;
//# rotational air resistance
// Gyro is the rotation speed in deg/s
// update rotational rates in body frame
ahrs.gyro.X += rot_accel.X * dt;
ahrs.gyro.Y += rot_accel.Y * dt;
ahrs.gyro.Z += rot_accel.Z * dt;
//ahrs.gyro.z += 200;
ahrs.gyro.Z *= .995;// some drag
// ahrs.dcm = Matrix3D.Identity;
// move earth frame to body frame
Vector3D tmp = Matrix3D.Transform(ahrs.dcm,ahrs.gyro) ;//ahrs.dcm.transformVector(ahrs.gyro);
// update attitude:
ahrs.dcm += new Matrix3D(new Vector3D((tmp.X/100) * dt,0,0),new Vector3D(0,(tmp.Y/100) * dt,0),new Vector3D(0,0,(tmp.Z/100) * dt));
//ahrs.dcm.appendRotation((tmp.X/100) * dt, Vector3D.X_AXIS); // ROLL
//ahrs.dcm.appendRotation((tmp.Y/100) * dt, Vector3D.Y_AXIS); // PITCH
//ahrs.dcm.appendRotation((tmp.Z/100) * dt, Vector3D.Z_AXIS); // YAW
// ------------------------------------
// calc thrust
// ------------------------------------
//get_motor_output returns 0 : 1000
_thrust += motor_output[0] * thrust_scale;
_thrust += motor_output[1] * thrust_scale;
_thrust += motor_output[2] * thrust_scale;
_thrust += motor_output[3] * thrust_scale;
Vector3D accel_body = new Vector3D(0, 0, (_thrust * -.9) / g.mass);
//var accel_body:Vector3D = new Vector3D(0, 0, 0);
Vector3D accel_earth = Matrix3D.Transform(ahrs.dcm,(accel_body));
angle3D = Matrix3D.Transform(ahrs.dcm,(angle3D));
//trace(ahrs.gyro.y, accel_earth.x);
//trace(ahrs.gyro.x, ahrs.gyro.y, ahrs.gyro.z);
// ------------------------------------
// calc copter velocity
// ------------------------------------
// calc Drag
drag.X = .5 * g.airDensity * airspeed.X * airspeed.X * g.dragCE * g.crossSection;
drag.Y = .5 * g.airDensity * airspeed.Y * airspeed.Y * g.dragCE * g.crossSection;
drag.Z = .5 * g.airDensity * airspeed.Z * airspeed.Z * g.dragCE * g.crossSection;
///*
// this calulation includes wind
if(airspeed.X >= 0)
accel_earth.X -= drag.X;
else
accel_earth.X += drag.X;
// Add in Drag
if(airspeed.Y >= 0)
accel_earth.Y -= drag.Y;
else
accel_earth.Y += drag.Y;
if(airspeed.Z <= 0)
accel_earth.Z -= drag.Z;
else
accel_earth.Z += drag.Z;
//*/
// hacked vert disturbance
accel_earth.Z += _jump_z * dt;
_jump_z *= .999;
// Add in Gravity
accel_earth.Z += gravity;
if(accel_earth.Z < 0)
accel_earth.Z *=.9;
if(position.Z <=.11 && accel_earth.Z > 0){
accel_earth.Z = 0;
}
velocity.X += (accel_earth.X * dt); // + : Forward (North)
velocity.Y += (accel_earth.Y * dt); // + : Right (East)
velocity.Z -= (accel_earth.Z * dt); // + : Up
//trace(Math.floor(velocity.x),Math.floor(velocity.y),Math.floor(velocity.z));
// ------------------------------------
// calc inertia
// ------------------------------------
// work out acceleration as seen by the accelerometers. It sees the kinematic
// acceleration (ie. real movement), plus gravity
Matrix3D dcm_t = ahrs.dcm.Clone();
dcm_t.Transpose();
double t = accel_earth.Z;
accel_earth.Z -= gravity;
ahrs.accel = Matrix3D.Transform(dcm_t,(accel_earth));
ahrs.accel *= 0.01;
//ahrs.accel = accel_earth.clone();
ahrs.accel.X *= g.accel_bias_x;
ahrs.accel.Y *= g.accel_bias_y;
ahrs.accel.Z *= g.accel_bias_z;
// ------------------------------------
// calc Position
// ------------------------------------
position.Y += velocity.X * dt;
position.X += velocity.Y * dt;
position.Z += velocity.Z * dt;
position.Z = Math.Min(position.Z, 4000);
// XXX Force us to 3m above ground
//position.z = 300;
airspeed.X = (velocity.X);// - wind.x);
airspeed.Y = (velocity.Y);// - wind.y);
airspeed.Z = velocity.Z;
// Altitude
// --------
if(position.Z <=.1){
position.Z = .1;
velocity.X = 0;
velocity.Y = 0;
velocity.Z = 0;
airspeed.X = 0;
airspeed.Y = 0;
airspeed.Z = 0;
//ahrs.init();
}
// get omega - the simulated Gyro output
ahrs.omega.X = radiansx100(ahrs.gyro.X);
ahrs.omega.Y = radiansx100(ahrs.gyro.Y);
ahrs.omega.Z = radiansx100(ahrs.gyro.Z);
// get the Eulers output
v3 = new Vector3D(Math.Atan2(-ahrs.dcm.M23, ahrs.dcm.M22), Math.Asin(ahrs.dcm.M21), Math.Atan2(-ahrs.dcm.M31, ahrs.dcm.M11));// ahrs.dcm.decompose();
ahrs.roll_sensor = Math.Floor(degrees(v3.X) * 100);
ahrs.pitch_sensor = Math.Floor(degrees(v3.Y) * 100);
ahrs.yaw_sensor = Math.Floor(degrees(v3.Z) * 100);
// store the position for the GPS object
loc.X = position.X;
loc.Y = position.Y;
loc.Z = position.Z;
}
public double constrain(double val, double min, double max)
{
val = Math.Max(val, min);
val = Math.Min(val, max);
return val;
}
public double wrap_180(int error)
{
if (error > 18000) error -= 36000;
if (error < -18000) error += 36000;
return error;
}
public int wrap_360(int error)
{
if (error > 36000) error -= 36000;
if (error < 0) error += 36000;
return error;
}
public double radiansx100(double n)
{
return 0.000174532925 * n;
}
public double degreesx100(double r)
{
return r * 5729.57795;
}
public double degrees(double r)
{
return r * 57.2957795;
}
public double radians(double n)
{
return 0.0174532925 * n;
}
}
}

View File

@ -0,0 +1,179 @@
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using YLScsDrawing.Drawing3d;
namespace ArdupilotMega.HIL
{
public class Matrix3
{
// '''a 3x3 matrix, intended as a rotation matrix'''
Matrix3 self;
Vector3 a;
Vector3 b;
Vector3 c;
public Matrix3()
{
self = this;
self.identity();
}
public Matrix3(Vector3 a, Vector3 b, Vector3 c)
{
self = this;
this.a = a;
this.b = b;
this.c = c;
}
public new string ToString()
{
return String.Format("Matrix3(({0}, {1}, {2}), ({3}, {4}, {5}), ({6}, {7}, {8}))",
self.a.x, self.a.y, self.a.z,
self.b.x, self.b.y, self.b.z,
self.c.x, self.c.y, self.c.z);
}
public void identity()
{
self.a = new Vector3(1, 0, 0);
self.b = new Vector3(0, 1, 0);
self.c = new Vector3(0, 0, 1);
}
public Matrix3 transposed()
{
return new Matrix3(new Vector3(self.a.x, self.b.x, self.c.x),
new Vector3(self.a.y, self.b.y, self.c.y),
new Vector3(self.a.z, self.b.z, self.c.z));
}
public void from_euler(double roll, double pitch, double yaw)
{
// '''fill the matrix from Euler angles in radians'''
double cp = Utils.cos(pitch);
double sp = Utils.sin(pitch);
double sr = Utils.sin(roll);
double cr = Utils.cos(roll);
double sy = Utils.sin(yaw);
double cy = Utils.cos(yaw);
self.a.x = cp * cy;
self.a.y = (sr * sp * cy) - (cr * sy);
self.a.z = (cr * sp * cy) + (sr * sy);
self.b.x = cp * sy;
self.b.y = (sr * sp * sy) + (cr * cy);
self.b.z = (cr * sp * sy) - (sr * cy);
self.c.x = -sp;
self.c.y = sr * cp;
self.c.z = cr * cp;
}
public void to_euler(ref double roll, ref double pitch, ref double yaw)
{
// '''find Euler angles for the matrix'''
if (self.c.x >= 1.0)
pitch = Math.PI;
else if (self.c.x <= -1.0)
pitch = -Math.PI;
else
pitch = -Utils.asin(self.c.x);
roll = Utils.atan2(self.c.y, self.c.z);
yaw = Utils.atan2(self.b.x, self.a.x);
//return (roll, pitch, yaw)
}
public static Matrix3 operator +(Matrix3 self, Matrix3 m)
{
return new Matrix3(self.a + m.a, self.b + m.b, self.c + m.c);
}
public static Matrix3 operator -(Matrix3 self, Matrix3 m)
{
return new Matrix3(self.a - m.a, self.b - m.b, self.c - m.c);
}
public static Vector3 operator *(Matrix3 self, Vector3 v)
{
return new Vector3(self.a.x * v.x + self.a.y * v.y + self.a.z * v.z,
self.b.x * v.x + self.b.y * v.y + self.b.z * v.z,
self.c.x * v.x + self.c.y * v.y + self.c.z * v.z);
}
public static Matrix3 operator *(Matrix3 self, Matrix3 m)
{
return new Matrix3(new Vector3(self.a.x * m.a.x + self.a.y * m.b.x + self.a.z * m.c.x,
self.a.x * m.a.y + self.a.y * m.b.y + self.a.z * m.c.y,
self.a.x * m.a.z + self.a.y * m.b.z + self.a.z * m.c.z),
new Vector3(self.b.x * m.a.x + self.b.y * m.b.x + self.b.z * m.c.x,
self.b.x * m.a.y + self.b.y * m.b.y + self.b.z * m.c.y,
self.b.x * m.a.z + self.b.y * m.b.z + self.b.z * m.c.z),
new Vector3(self.c.x * m.a.x + self.c.y * m.b.x + self.c.z * m.c.x,
self.c.x * m.a.y + self.c.y * m.b.y + self.c.z * m.c.y,
self.c.x * m.a.z + self.c.y * m.b.z + self.c.z * m.c.z));
}
public static Matrix3 operator *(Matrix3 self, double v)
{
return new Matrix3(self.a * v, self.b * v, self.c * v);
}
public static Matrix3 operator /(Matrix3 self, double v)
{
return new Matrix3(self.a / v, self.b / v, self.c / v);
}
public static Matrix3 operator -(Matrix3 self)
{
return new Matrix3(-self.a, -self.b, -self.c);
}
public Matrix3 copy()
{
return new Matrix3(self.a.copy(), self.b.copy(), self.c.copy());
}
public void rotate(Vector3 g)
{
// '''rotate the matrix by a given amount on 3 axes'''
Matrix3 temp_matrix = new Matrix3(self.a.copy(), self.b.copy(), self.c.copy());
temp_matrix.a.x = a.y * g.z - a.z * g.y;
temp_matrix.a.y = a.z * g.x - a.x * g.z;
temp_matrix.a.z = a.x * g.y - a.y * g.x;
temp_matrix.b.x = b.y * g.z - b.z * g.y;
temp_matrix.b.y = b.z * g.x - b.x * g.z;
temp_matrix.b.z = b.x * g.y - b.y * g.x;
temp_matrix.c.x = c.y * g.z - c.z * g.y;
temp_matrix.c.y = c.z * g.x - c.x * g.z;
temp_matrix.c.z = c.x * g.y - c.y * g.x;
self.a += temp_matrix.a;
self.b += temp_matrix.b;
self.c += temp_matrix.c;
}
public void normalize()
{
// '''re-normalise a rotation matrix'''
Vector3 error = self.a * self.b;
Vector3 t0 = self.a - (self.b * (0.5 * error));
Vector3 t1 = self.b - (self.a * (0.5 * error));
Vector3 t2 = t0 % t1;
self.a = t0 * (1.0 / t0.length());
self.b = t1 * (1.0 / t1.length());
self.c = t2 * (1.0 / t2.length());
}
public double trace()
{
// '''the trace of the matrix'''
return self.a.x + self.b.y + self.c.z;
}
}
}

View File

@ -7,6 +7,7 @@ using log4net;
using YLScsDrawing.Drawing3d;
using ArdupilotMega.HIL;
namespace ArdupilotMega.HIL
{
public class Motor : Utils
@ -116,7 +117,7 @@ namespace ArdupilotMega.HIL
double terminal_rotation_rate;
Motor[] motors;
Vector3d old_position;
Vector3 old_position;
//# scaling from total motor power to Newtons. Allows the copter
@ -136,7 +137,7 @@ namespace ArdupilotMega.HIL
motor_speed = new double[motors.Length];
hover_throttle = 0.37;
terminal_velocity = 30.0;
terminal_rotation_rate = 4 * 360.0;
terminal_rotation_rate = 4 * 360.0 * deg2rad;
thrust_scale = (mass * gravity) / (motors.Length * hover_throttle);
@ -145,58 +146,28 @@ namespace ArdupilotMega.HIL
double scale_rc(int sn, float servo, float min, float max)
{
float min_pwm = 1000;
float max_pwm = 2000;
//'''scale a PWM value''' # default to servo range of 1000 to 2000
if (MainV2.comPort.param.Count > 0)
{
min_pwm = int.Parse(MainV2.comPort.param["RC3_MIN"].ToString());
max_pwm = int.Parse(MainV2.comPort.param["RC3_MAX"].ToString());
}
float p = (servo - min_pwm) / (max_pwm - min_pwm);
float v = min + p * (max - min);
if (v < min)
v = min;
if (v > max)
v = max;
return v;
return ((servo - 1000) / 1000.0);
}
public void update(ref double[] servos, ArdupilotMega.GCSViews.Simulation.FGNetFDM fdm)
{
for (int i = 0; i < servos.Length; i++)
{
if (servos[i] <= 0.0)
var servo = servos[(int)self.motors[i].servo - 1];
if (servo <= 0.0)
{
motor_speed[i] = 0;
}
else
{
motor_speed[i] = scale_rc(i, (float)servos[i], 0.0f, 1.0f);
motor_speed[i] = scale_rc(i, (float)servo, 0.0f, 1.0f);
//servos[i] = motor_speed[i];
}
}
double[] m = motor_speed;
/*
roll = 0;
pitch = 0;
yaw = 0;
roll_rate = 0;
pitch_rate = 0;
yaw_rate = 0;
*/
// Console.WriteLine("\nin m {0:0.000000} {1:0.000000} {2:0.000000} {3:0.000000}", m[0], m[1], m[2], m[3]);
// Console.WriteLine("in vel {0:0.000000} {1:0.000000} {2:0.000000}", velocity.X, velocity.Y, velocity.Z);
//Console.WriteLine("in r {0:0.000000} p {1:0.000000} y {2:0.000000} - r {3:0.000000} p {4:0.000000} y {5:0.000000}", roll, pitch, yaw, roll_rate, pitch_rate, yaw_rate);
// m[0] *= 0.5;
//# how much time has passed?
DateTime t = DateTime.Now;
TimeSpan delta_time = t - last_time; // 0.02
@ -208,218 +179,133 @@ namespace ArdupilotMega.HIL
}
// rotational acceleration, in degrees/s/s, in body frame
double roll_accel = 0.0;
double pitch_accel = 0.0;
double yaw_accel = 0.0;
Vector3 rot_accel = new Vector3(0, 0, 0);
double thrust = 0.0;
foreach (var i in range((self.motors.Length)))
{
roll_accel += (-5000.0 * deg2rad) * sin(radians(self.motors[i].angle)) * m[i];
pitch_accel += (5000.0 * deg2rad) * cos(radians(self.motors[i].angle)) * m[i];
rot_accel.x += -radians(5000.0) * sin(radians(self.motors[i].angle)) * m[i];
rot_accel.y += radians(5000.0) * cos(radians(self.motors[i].angle)) * m[i];
if (self.motors[i].clockwise)
{
yaw_accel -= m[i] * 400.0 * deg2rad;
rot_accel.z -= m[i] * radians(400.0);
}
else
{
yaw_accel += m[i] * 400.0 * deg2rad;
rot_accel.z += m[i] * radians(400.0);
}
thrust += m[i] * self.thrust_scale; // newtons
}
// rotational resistance
roll_accel -= (self.pDeg / self.terminal_rotation_rate) * (5000.0 * deg2rad);
pitch_accel -= (self.qDeg / self.terminal_rotation_rate) * (5000.0 * deg2rad);
yaw_accel -= (self.rDeg / self.terminal_rotation_rate) * (400.0 * deg2rad);
// rotational air resistance
rot_accel.x -= self.gyro.x * radians(5000.0) / self.terminal_rotation_rate;
rot_accel.y -= self.gyro.y * radians(5000.0) / self.terminal_rotation_rate;
rot_accel.z -= self.gyro.z * radians(400.0) / self.terminal_rotation_rate;
//Console.WriteLine("roll {0} {1} {2}", roll_accel, roll_rate, roll);
// Console.WriteLine("rot_accel " + rot_accel.ToString());
//# update rotational rates in body frame
self.pDeg += roll_accel * delta_time.TotalSeconds;
self.qDeg += pitch_accel * delta_time.TotalSeconds;
self.rDeg += yaw_accel * delta_time.TotalSeconds;
// update rotational rates in body frame
self.gyro += rot_accel * delta_time.TotalSeconds;
// Console.WriteLine("roll {0} {1} {2}", roll_accel, roll_rate, roll);
// Console.WriteLine("gyro " + gyro.ToString());
// calculate rates in earth frame
// update attitude
self.dcm.rotate(self.gyro * delta_time.TotalSeconds);
self.dcm.normalize();
var answer = BodyRatesToEarthRates(self.roll, self.pitch, self.yaw,
self.pDeg, self.qDeg, self.rDeg);
self.roll_rate = answer.Item1;
self.pitch_rate = answer.Item2;
self.yaw_rate = answer.Item3;
// self.roll_rate = pDeg;
// self.pitch_rate = qDeg;
// self.yaw_rate = rDeg;
// air resistance
Vector3 air_resistance = -self.velocity * (self.gravity / self.terminal_velocity);
//# update rotation
roll += roll_rate * delta_time.TotalSeconds;
pitch += pitch_rate * delta_time.TotalSeconds;
yaw += yaw_rate * delta_time.TotalSeconds;
accel_body = new Vector3(0, 0, -thrust / self.mass);
Vector3 accel_earth = self.dcm * accel_body;
accel_earth += new Vector3(0, 0, self.gravity);
accel_earth += air_resistance;
// add in some wind
// accel_earth += self.wind.accel(self.velocity);
// Console.WriteLine("roll {0} {1} {2}", roll_accel, roll_rate, roll);
// if we're on the ground, then our vertical acceleration is limited
// to zero. This effectively adds the force of the ground on the aircraft
if (self.on_ground() && accel_earth.z > 0)
accel_earth.z = 0;
//Console.WriteLine("r {0:0.0} p {1:0.0} y {2:0.0} - r {3:0.0} p {4:0.0} y {5:0.0} ms {6:0.000}", roll, pitch, yaw, roll_rate, pitch_rate, yaw_rate, delta_time.TotalSeconds);
// work out acceleration as seen by the accelerometers. It sees the kinematic
// acceleration (ie. real movement), plus gravity
self.accel_body = self.dcm.transposed() * (accel_earth + new Vector3(0, 0, -self.gravity));
//# air resistance
Vector3d air_resistance = -velocity * (gravity / terminal_velocity);
// new velocity vector
self.velocity += accel_earth * delta_time.TotalSeconds;
//# normalise rotations
normalise();
if (double.IsNaN(velocity.x) || double.IsNaN(velocity.y) || double.IsNaN(velocity.z))
velocity = new Vector3();
double accel = thrust / mass;
// new position vector
old_position = self.position.copy();
self.position += self.velocity * delta_time.TotalSeconds;
//Console.WriteLine("in {0:0.000000} {1:0.000000} {2:0.000000} {3:0.000000}", roll, pitch, yaw, accel);
Vector3d accel3D = RPY_to_XYZ(roll, pitch, yaw, accel);
//Console.WriteLine("accel3D " + accel3D.X + " " + accel3D.Y + " " + accel3D.Z);
accel3D += new Vector3d(0, 0, -gravity);
accel3D += air_resistance;
Random rand = new Random();
//velocity.X += .02 + rand.NextDouble() * .03;
//velocity.Y += .02 + rand.NextDouble() * .03;
//# new velocity vector
velocity += accel3D * delta_time.TotalSeconds;
this.accel = accel3D;
//# new position vector
old_position = new Vector3d(position);
position += velocity * delta_time.TotalSeconds;
// Console.WriteLine(fdm.agl + " "+ fdm.altitude);
//Console.WriteLine("Z {0} halt {1} < gl {2} fh {3}" ,position.Z , home_altitude , ground_level , frame_height);
if (home_latitude == 0 || home_latitude > 90 || home_latitude < -90 || home_longitude == 0)
if (home_latitude == 0)
{
this.home_latitude = fdm.latitude * rad2deg;
this.home_longitude = fdm.longitude * rad2deg;
this.home_altitude = fdm.altitude * ft2m;
this.ground_level = this.home_altitude;
this.altitude = fdm.altitude * ft2m;
this.latitude = fdm.latitude * rad2deg;
this.longitude = fdm.longitude * rad2deg;
home_latitude = fdm.latitude * rad2deg;
home_longitude = fdm.longitude * rad2deg;
home_altitude = altitude;
}
//# constrain height to the ground
if (position.Z + home_altitude < ground_level + frame_height)
// constrain height to the ground
if (self.on_ground())
{
if (old_position.Z + home_altitude > ground_level + frame_height)
{
// Console.WriteLine("Hit ground at {0} m/s", (-velocity.Z));
}
velocity = new Vector3d(0, 0, 0);
roll_rate = 0;
pitch_rate = 0;
yaw_rate = 0;
roll = 0;
pitch = 0;
position = new Vector3d(position.X, position.Y,
ground_level + frame_height - home_altitude + 0);
// Console.WriteLine("here " + position.Z);
if (!self.on_ground(old_position))
Console.WriteLine("Hit ground at {0} m/s", (self.velocity.z));
self.velocity = new Vector3(0, 0, 0);
// zero roll/pitch, but keep yaw
double r = 0;
double p = 0;
double y = 0;
self.dcm.to_euler(ref r, ref p, ref y);
self.dcm.from_euler(0, 0, y);
self.position = new Vector3(self.position.x, self.position.y,
-(self.ground_level + self.frame_height - self.home_altitude));
}
//# update lat/lon/altitude
update_position();
// update lat/lon/altitude
self.update_position(delta_time.TotalSeconds);
// send to apm
#if MAVLINK10
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();
#endif
MAVLink.mavlink_hil_state_t hilstate = new MAVLink.mavlink_hil_state_t();
ArdupilotMega.MAVLink.mavlink_attitude_t att = new ArdupilotMega.MAVLink.mavlink_attitude_t();
hilstate.time_usec = (UInt64)DateTime.Now.Ticks; // microsec
ArdupilotMega.MAVLink.mavlink_vfr_hud_t asp = new ArdupilotMega.MAVLink.mavlink_vfr_hud_t();
hilstate.lat = (int)(latitude * 1e7); // * 1E7
hilstate.lon = (int)(longitude * 1e7); // * 1E7
hilstate.alt = (int)(altitude * 1000); // mm
att.roll = (float)roll * deg2rad;
att.pitch = (float)pitch * deg2rad;
att.yaw = (float)yaw * deg2rad;
att.rollspeed = (float)roll_rate * deg2rad;
att.pitchspeed = (float)pitch_rate * deg2rad;
att.yawspeed = (float)yaw_rate * deg2rad;
self.dcm.to_euler(ref roll, ref pitch, ref yaw);
#if MAVLINK10
gps.alt = ((int)(altitude * 1000));
gps.fix_type = 3;
gps.vel = (ushort)(Math.Sqrt((velocity.X * velocity.X) + (velocity.Y * velocity.Y)) * 100);
gps.cog = (ushort)((((Math.Atan2(velocity.Y, velocity.X) * rad2deg) + 360) % 360) * 100);
gps.lat = (int)(latitude* 1.0e7);
gps.lon = (int)(longitude * 1.0e7);
gps.time_usec = ((ulong)DateTime.Now.Ticks);
asp.airspeed = gps.vel;
#else
gps.alt = ((float)(altitude));
gps.fix_type = 3;
gps.lat = ((float)latitude);
gps.lon = ((float)longitude);
gps.usec = ((ulong)DateTime.Now.Ticks);
//Random rand = new Random();
//gps.alt += (rand.Next(100) - 50) / 100.0f;
//gps.lat += (float)((rand.NextDouble() - 0.5) * 0.00005);
//gps.lon += (float)((rand.NextDouble() - 0.5) * 0.00005);
//gps.v += (float)(rand.NextDouble() - 0.5) * 1.0f;
gps.v = ((float)Math.Sqrt((velocity.X * velocity.X) + (velocity.Y * velocity.Y)));
gps.hdg = (float)(((Math.Atan2(velocity.Y, velocity.X) * rad2deg) + 360) % 360); ;
asp.airspeed = gps.v;
#endif
MainV2.comPort.sendPacket(att);
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
MainV2.comPort.sendPacket(pres);
MainV2.comPort.sendPacket(asp);
if (framecount % 120 == 0)
{// 50 / 10 = 5 hz
MainV2.comPort.sendPacket(gps);
//Console.WriteLine(DateTime.Now.Millisecond + " GPS" );
if (double.IsNaN(roll))
{
self.dcm.identity();
}
framecount++;
}
hilstate.roll = (float)roll;
hilstate.pitch = (float)pitch;
hilstate.yaw = (float)yaw;
public static Vector3d RPY_to_XYZ(double roll, double pitch, double yaw, double length)
{
Vector3d v = new Vector3d(0, 0, length);
v = new_rotate_euler(-deg2rad * (pitch), 0, -deg2rad * (roll)) * v;
v = new_rotate_euler(0, deg2rad * (yaw), 0) * v;
return v;
}
Vector3 earth_rates = Utils.BodyRatesToEarthRates(dcm, gyro);
public static Quaternion new_rotate_euler(double heading, double attitude, double bank)
{
Quaternion Q = new Quaternion();
double c1 = Math.Cos(heading / 2);
double s1 = Math.Sin(heading / 2);
double c2 = Math.Cos(attitude / 2);
double s2 = Math.Sin(attitude / 2);
double c3 = Math.Cos(bank / 2);
double s3 = Math.Sin(bank / 2);
hilstate.rollspeed = (float)earth_rates.x;
hilstate.pitchspeed = (float)earth_rates.y;
hilstate.yawspeed = (float)earth_rates.z;
Q.W = c1 * c2 * c3 - s1 * s2 * s3;
Q.X = s1 * s2 * c3 + c1 * c2 * s3;
Q.Y = s1 * c2 * c3 + c1 * s2 * s3;
Q.Z = c1 * s2 * c3 - s1 * c2 * s3;
return Q;
hilstate.vx = (short)(velocity.y * 100); // m/s * 100
hilstate.vy = (short)(velocity.x * 100); // m/s * 100
hilstate.vz = 0; // m/s * 100
hilstate.xacc = (short)(accelerometer.x * 1000); // (mg)
hilstate.yacc = (short)(accelerometer.y * 1000); // (mg)
hilstate.zacc = (short)(accelerometer.z * 1000); // (mg)
MainV2.comPort.sendPacket(hilstate);
}
}
}

View File

@ -7,10 +7,10 @@ namespace ArdupilotMega.HIL
{
public class Utils
{
public const float rad2deg = (float)(180 / System.Math.PI);
public const float deg2rad = (float)(1.0 / rad2deg);
public const float ft2m = (float)(1.0 / 3.2808399);
public const float kts2fps = (float)1.68780986;
public const double rad2deg = (180 / System.Math.PI);
public const double deg2rad = (1.0 / rad2deg);
public const double ft2m = (1.0 / 3.2808399);
public const double kts2fps = 1.68780986;
public static double sin(double val)
{
@ -20,6 +20,14 @@ namespace ArdupilotMega.HIL
{
return System.Math.Cos(val);
}
public static double asin(double val)
{
return System.Math.Asin(val);
}
public static double atan2(double val, double val2)
{
return System.Math.Atan2(val, val2);
}
public static double radians(double val)
{
return val * deg2rad;
@ -97,7 +105,7 @@ namespace ArdupilotMega.HIL
var R = Po * (sin(phi) * sin(psi) + cos(phi) * cos(psi) * sin(theta)) - Qo * (cos(psi) * sin(phi) - cos(phi) * sin(psi) * sin(theta)) + Ro * cos(phi) * cos(theta);
// P = 0;
// P = 0;
//Q = 0;
//R = 0;
@ -160,7 +168,7 @@ namespace ArdupilotMega.HIL
* */
}
public static Tuple<double, double, double> OGLtoBCBF(double phi, double theta, double psi,double x, double y, double z)
public static Tuple<double, double, double> OGLtoBCBF(double phi, double theta, double psi, double x, double y, double z)
{
double x_NED, y_NED, z_NED;
double Cr, Cp, Cy;
@ -231,21 +239,25 @@ namespace ArdupilotMega.HIL
z = Z_plane;
}
public static Tuple<double, double, double> BodyRatesToEarthRates(double roll, double pitch, double yaw, double pDeg, double qDeg, double rDeg)
public static Vector3 BodyRatesToEarthRates(Matrix3 dcm, Vector3 gyro)
{
//convert the angular velocities from body frame to
//'''convert the angular velocities from body frame to
//earth frame.
//all inputs and outputs are in degrees
//all inputs and outputs are in radians/s
//returns a tuple, (rollRate,pitchRate,yawRate)
//returns a earth rate vector
//'''
var p = radians(pDeg);
var q = radians(qDeg);
var r = radians(rDeg);
var p = gyro.x;
var q = gyro.y;
var r = gyro.z;
var phi = radians(roll);
var theta = radians(pitch);
double phi = 0;
double theta = 0;
double psi = 0;
dcm.to_euler(ref phi, ref theta, ref psi);
var phiDot = p + tan(theta) * (q * sin(phi) + r * cos(phi));
var thetaDot = q * cos(phi) - r * sin(phi);
@ -253,7 +265,7 @@ namespace ArdupilotMega.HIL
theta += 1.0e-10;
var psiDot = (q * sin(phi) + r * cos(phi)) / cos(theta);
return new Tuple<double, double, double>(degrees(phiDot), degrees(thetaDot), degrees(psiDot));
return new Vector3((phiDot), (thetaDot), (psiDot));
}
}
}

View File

@ -0,0 +1,107 @@
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
namespace ArdupilotMega.HIL
{
public class Vector3
{
Vector3 self;
public double x;
public double y;
public double z;
public Vector3(double x = 0, double y = 0, double z = 0)
{
self = this;
this.x = x;
this.y = y;
this.z = z;
}
public new string ToString() {
return String.Format("Vector3({0}, {1}, {2})",self.x,
self.y,
self.z);
}
public static Vector3 operator +(Vector3 self, Vector3 v) {
return new Vector3(self.x + v.x,
self.y + v.y,
self.z + v.z);
}
public static Vector3 operator -(Vector3 self, Vector3 v) {
return new Vector3(self.x - v.x,
self.y - v.y,
self.z - v.z);
}
public static Vector3 operator -(Vector3 self) {
return new Vector3(-self.x, -self.y, -self.z);
}
public static Vector3 operator *(Vector3 self, Vector3 v) {
// '''dot product'''
return new Vector3(self.x*v.x + self.y*v.y + self.z*v.z);
}
public static Vector3 operator *(Vector3 self, double v) {
return new Vector3(self.x * v,
self.y * v,
self.z * v);
}
public static Vector3 operator *(double v, Vector3 self)
{
return (self * v);
}
public static Vector3 operator /(Vector3 self, double v) {
return new Vector3(self.x / v,
self.y / v,
self.z / v);
}
public static Vector3 operator %(Vector3 self, Vector3 v) {
// '''cross product'''
return new Vector3(self.y*v.z - self.z*v.y,
self.z*v.x - self.x*v.z,
self.x*v.y - self.y*v.x);
}
public Vector3 copy() {
return new Vector3(self.x, self.y, self.z);
}
public double length() {
return Math.Sqrt(self.x*self.x + self.y*self.y + self.z*self.z);
}
public void zero() {
self.x = self.y = self.z = 0;
}
// public double angle (Vector3 self, Vector3 v) {
// '''return the angle between this vector and another vector'''
// return Math.Acos(self * v) / (self.length() * v.length());
// }
public Vector3 normalized(){
return self / self.length();
}
public void normalize() {
Vector3 v = self.normalized();
self.x = v.x;
self.y = v.y;
self.z = v.z;
}
}
}

View File

@ -8,7 +8,7 @@ namespace ArdupilotMega
#if MAVLINK10
partial class MAVLink
{
public const string MAVLINK_BUILD_DATE = "Sun Apr 8 12:29:46 2012";
public const string MAVLINK_BUILD_DATE = "Thu Jul 26 18:28:25 2012";
public const string MAVLINK_WIRE_PROTOCOL_VERSION = "1.0";
public const int MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 42;
@ -25,11 +25,11 @@ namespace ArdupilotMega
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_LENGTHS = new byte[] {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0};
public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 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, 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, 204, 49, 170, 44, 83, 46, 247};
public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 42, 21, 21, 144, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0};
public Type[] MAVLINK_MESSAGE_INFO = new Type[] {typeof( mavlink_heartbeat_t ), typeof( mavlink_sys_status_t ), typeof( mavlink_system_time_t ), null, typeof( mavlink_ping_t ), typeof( mavlink_change_operator_control_t ), typeof( mavlink_change_operator_control_ack_t ), typeof( mavlink_auth_key_t ), null, null, null, typeof( mavlink_set_mode_t ), null, null, null, null, null, null, null, null, typeof( mavlink_param_request_read_t ), typeof( mavlink_param_request_list_t ), typeof( mavlink_param_value_t ), typeof( mavlink_param_set_t ), typeof( mavlink_gps_raw_int_t ), typeof( mavlink_gps_status_t ), typeof( mavlink_scaled_imu_t ), typeof( mavlink_raw_imu_t ), typeof( mavlink_raw_pressure_t ), typeof( mavlink_scaled_pressure_t ), typeof( mavlink_attitude_t ), typeof( mavlink_attitude_quaternion_t ), typeof( mavlink_local_position_ned_t ), typeof( mavlink_global_position_int_t ), typeof( mavlink_rc_channels_scaled_t ), typeof( mavlink_rc_channels_raw_t ), typeof( mavlink_servo_output_raw_t ), typeof( mavlink_mission_request_partial_list_t ), typeof( mavlink_mission_write_partial_list_t ), typeof( mavlink_mission_item_t ), typeof( mavlink_mission_request_t ), typeof( mavlink_mission_set_current_t ), typeof( mavlink_mission_current_t ), typeof( mavlink_mission_request_list_t ), typeof( mavlink_mission_count_t ), typeof( mavlink_mission_clear_all_t ), typeof( mavlink_mission_item_reached_t ), typeof( mavlink_mission_ack_t ), typeof( mavlink_set_gps_global_origin_t ), typeof( mavlink_gps_global_origin_t ), typeof( mavlink_set_local_position_setpoint_t ), typeof( mavlink_local_position_setpoint_t ), typeof( mavlink_global_position_setpoint_int_t ), typeof( mavlink_set_global_position_setpoint_int_t ), typeof( mavlink_safety_set_allowed_area_t ), typeof( mavlink_safety_allowed_area_t ), typeof( mavlink_set_roll_pitch_yaw_thrust_t ), typeof( mavlink_set_roll_pitch_yaw_speed_thrust_t ), typeof( mavlink_roll_pitch_yaw_thrust_setpoint_t ), typeof( mavlink_roll_pitch_yaw_speed_thrust_setpoint_t ), 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 Type[] MAVLINK_MESSAGE_INFO = new Type[] {typeof( mavlink_heartbeat_t ), typeof( mavlink_sys_status_t ), typeof( mavlink_system_time_t ), null, typeof( mavlink_ping_t ), typeof( mavlink_change_operator_control_t ), typeof( mavlink_change_operator_control_ack_t ), typeof( mavlink_auth_key_t ), null, null, null, typeof( mavlink_set_mode_t ), null, null, null, null, null, null, null, null, typeof( mavlink_param_request_read_t ), typeof( mavlink_param_request_list_t ), typeof( mavlink_param_value_t ), typeof( mavlink_param_set_t ), typeof( mavlink_gps_raw_int_t ), typeof( mavlink_gps_status_t ), typeof( mavlink_scaled_imu_t ), typeof( mavlink_raw_imu_t ), typeof( mavlink_raw_pressure_t ), typeof( mavlink_scaled_pressure_t ), typeof( mavlink_attitude_t ), typeof( mavlink_attitude_quaternion_t ), typeof( mavlink_local_position_ned_t ), typeof( mavlink_global_position_int_t ), typeof( mavlink_rc_channels_scaled_t ), typeof( mavlink_rc_channels_raw_t ), typeof( mavlink_servo_output_raw_t ), typeof( mavlink_mission_request_partial_list_t ), typeof( mavlink_mission_write_partial_list_t ), typeof( mavlink_mission_item_t ), typeof( mavlink_mission_request_t ), typeof( mavlink_mission_set_current_t ), typeof( mavlink_mission_current_t ), typeof( mavlink_mission_request_list_t ), typeof( mavlink_mission_count_t ), typeof( mavlink_mission_clear_all_t ), typeof( mavlink_mission_item_reached_t ), typeof( mavlink_mission_ack_t ), typeof( mavlink_set_gps_global_origin_t ), typeof( mavlink_gps_global_origin_t ), typeof( mavlink_set_local_position_setpoint_t ), typeof( mavlink_local_position_setpoint_t ), typeof( mavlink_global_position_setpoint_int_t ), typeof( mavlink_set_global_position_setpoint_int_t ), typeof( mavlink_safety_set_allowed_area_t ), typeof( mavlink_safety_allowed_area_t ), typeof( mavlink_set_roll_pitch_yaw_thrust_t ), typeof( mavlink_set_roll_pitch_yaw_speed_thrust_t ), typeof( mavlink_roll_pitch_yaw_thrust_setpoint_t ), typeof( mavlink_roll_pitch_yaw_speed_thrust_setpoint_t ), typeof( mavlink_set_quad_motors_setpoint_t ), typeof( mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t ), typeof( mavlink_nav_controller_output_t ), typeof( mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t ), typeof( mavlink_state_correction_t ), null, typeof( mavlink_request_data_stream_t ), typeof( mavlink_data_stream_t ), null, typeof( mavlink_manual_control_t ), typeof( mavlink_rc_channels_override_t ), null, null, null, typeof( mavlink_vfr_hud_t ), null, typeof( mavlink_command_long_t ), typeof( mavlink_command_ack_t ), null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_local_position_ned_system_global_offset_t ), typeof( mavlink_hil_state_t ), typeof( mavlink_hil_controls_t ), typeof( mavlink_hil_rc_inputs_raw_t ), null, null, null, null, null, null, null, typeof( mavlink_optical_flow_t ), typeof( mavlink_global_vision_position_estimate_t ), typeof( mavlink_vision_position_estimate_t ), typeof( mavlink_vision_speed_estimate_t ), typeof( mavlink_vicon_position_estimate_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_sensor_offsets_t ), typeof( mavlink_set_mag_offsets_t ), typeof( mavlink_meminfo_t ), typeof( mavlink_ap_adc_t ), typeof( mavlink_digicam_configure_t ), typeof( mavlink_digicam_control_t ), typeof( mavlink_mount_configure_t ), typeof( mavlink_mount_control_t ), typeof( mavlink_mount_status_t ), null, typeof( mavlink_fence_point_t ), typeof( mavlink_fence_fetch_point_t ), typeof( mavlink_fence_status_t ), typeof( mavlink_ahrs_t ), typeof( mavlink_simstate_t ), typeof( mavlink_hwstatus_t ), typeof( mavlink_radio_t ), typeof( mavlink_limits_status_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_memory_vect_t ), typeof( mavlink_debug_vect_t ), typeof( mavlink_named_value_float_t ), typeof( mavlink_named_value_int_t ), typeof( mavlink_statustext_t ), typeof( mavlink_debug_t ), null};
public const byte MAVLINK_VERSION = 2;
@ -127,8 +127,10 @@ namespace ArdupilotMega
OVERRIDE_GOTO=252,
///<summary> 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)| </summary>
MISSION_START=300,
///<summary> Arms / Disarms a component |1 to arm, 0 to disarm| </summary>
COMPONENT_ARM_DISARM=400,
///<summary> | </summary>
ENUM_END=301,
ENUM_END=401,
};
@ -160,6 +162,40 @@ namespace ArdupilotMega
};
/** @brief */
public enum LIMITS_STATE
{
///<summary> pre-initialization | </summary>
LIMITS_INIT=0,
///<summary> disabled | </summary>
LIMITS_DISABLED=1,
///<summary> checking limits | </summary>
LIMITS_ENABLED=2,
///<summary> a limit has been breached | </summary>
LIMITS_TRIGGERED=3,
///<summary> taking action eg. RTL | </summary>
LIMITS_RECOVERING=4,
///<summary> we're no longer in breach of a limit | </summary>
LIMITS_RECOVERED=5,
///<summary> | </summary>
ENUM_END=6,
};
/** @brief */
public enum LIMIT_MODULE
{
///<summary> pre-initialization | </summary>
LIMIT_GPSLOCK=1,
///<summary> disabled | </summary>
LIMIT_GEOFENCE=2,
///<summary> checking limits | </summary>
LIMIT_ALTITUDE=4,
///<summary> | </summary>
ENUM_END=5,
};
/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */
@ -194,6 +230,50 @@ namespace ArdupilotMega
};
/** @brief */
public enum MAV_TYPE
{
///<summary> Generic micro air vehicle. | </summary>
GENERIC=0,
///<summary> Fixed wing aircraft. | </summary>
FIXED_WING=1,
///<summary> Quadrotor | </summary>
QUADROTOR=2,
///<summary> Coaxial helicopter | </summary>
COAXIAL=3,
///<summary> Normal helicopter with tail rotor. | </summary>
HELICOPTER=4,
///<summary> Ground installation | </summary>
ANTENNA_TRACKER=5,
///<summary> Operator control unit / ground control station | </summary>
GCS=6,
///<summary> Airship, controlled | </summary>
AIRSHIP=7,
///<summary> Free balloon, uncontrolled | </summary>
FREE_BALLOON=8,
///<summary> Rocket | </summary>
ROCKET=9,
///<summary> Ground rover | </summary>
GROUND_ROVER=10,
///<summary> Surface vessel, boat, ship | </summary>
SURFACE_BOAT=11,
///<summary> Submarine | </summary>
SUBMARINE=12,
///<summary> Hexarotor | </summary>
HEXAROTOR=13,
///<summary> Octorotor | </summary>
OCTOROTOR=14,
///<summary> Octorotor | </summary>
TRICOPTER=15,
///<summary> Flapping wing | </summary>
FLAPPING_WING=16,
///<summary> Flapping wing | </summary>
KITE=17,
///<summary> | </summary>
ENUM_END=18,
};
/** @brief These flags encode the MAV mode. */
public enum MAV_MODE_FLAG
{
@ -312,48 +392,6 @@ namespace ArdupilotMega
};
/** @brief */
public enum MAV_TYPE
{
///<summary> Generic micro air vehicle. | </summary>
GENERIC=0,
///<summary> Fixed wing aircraft. | </summary>
FIXED_WING=1,
///<summary> Quadrotor | </summary>
QUADROTOR=2,
///<summary> Coaxial helicopter | </summary>
COAXIAL=3,
///<summary> Normal helicopter with tail rotor. | </summary>
HELICOPTER=4,
///<summary> Ground installation | </summary>
ANTENNA_TRACKER=5,
///<summary> Operator control unit / ground control station | </summary>
GCS=6,
///<summary> Airship, controlled | </summary>
AIRSHIP=7,
///<summary> Free balloon, uncontrolled | </summary>
FREE_BALLOON=8,
///<summary> Rocket | </summary>
ROCKET=9,
///<summary> Ground rover | </summary>
GROUND_ROVER=10,
///<summary> Surface vessel, boat, ship | </summary>
SURFACE_BOAT=11,
///<summary> Submarine | </summary>
SUBMARINE=12,
///<summary> Hexarotor | </summary>
HEXAROTOR=13,
///<summary> Octorotor | </summary>
OCTOROTOR=14,
///<summary> Octorotor | </summary>
TRICOPTER=15,
///<summary> Flapping wing | </summary>
FLAPPING_WING=16,
///<summary> | </summary>
ENUM_END=17,
};
/** @brief */
public enum MAV_COMPONENT
{
@ -522,28 +560,6 @@ namespace ArdupilotMega
};
/** @brief type of a mavlink parameter */
public enum MAV_VAR
{
///<summary> 32 bit float | </summary>
FLOAT=0,
///<summary> 8 bit unsigned integer | </summary>
UINT8=1,
///<summary> 8 bit signed integer | </summary>
INT8=2,
///<summary> 16 bit unsigned integer | </summary>
UINT16=3,
///<summary> 16 bit signed integer | </summary>
INT16=4,
///<summary> 32 bit unsigned integer | </summary>
UINT32=5,
///<summary> 32 bit signed integer | </summary>
INT32=6,
///<summary> | </summary>
ENUM_END=7,
};
/** @brief result from a mavlink command */
public enum MAV_RESULT
{
@ -600,6 +616,30 @@ namespace ArdupilotMega
};
/** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */
public enum MAV_SEVERITY
{
///<summary> System is unusable. This is a "panic" condition. | </summary>
EMERGENCY=0,
///<summary> Action should be taken immediately. Indicates error in non-critical systems. | </summary>
ALERT=1,
///<summary> Action must be taken immediately. Indicates failure in a primary system. | </summary>
CRITICAL=2,
///<summary> Indicates an error in secondary/redundant systems. | </summary>
ERROR=3,
///<summary> Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | </summary>
WARNING=4,
///<summary> An unusual event has occured, though not an error condition. This should be investigated for the root cause. | </summary>
NOTICE=5,
///<summary> Normal operational messages. Useful for logging. No action is required for these messages. | </summary>
INFO=6,
///<summary> Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | </summary>
DEBUG=7,
///<summary> | </summary>
ENUM_END=8,
};
public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS = 150;
[StructLayout(LayoutKind.Sequential,Pack=1,Size=42)]
@ -931,6 +971,32 @@ namespace ArdupilotMega
};
public const byte MAVLINK_MSG_ID_LIMITS_STATUS = 167;
[StructLayout(LayoutKind.Sequential,Pack=1,Size=22)]
public struct mavlink_limits_status_t
{
/// <summary> time of last breach in milliseconds since boot </summary>
public UInt32 last_trigger;
/// <summary> time of last recovery action in milliseconds since boot </summary>
public UInt32 last_action;
/// <summary> time of last successful recovery in milliseconds since boot </summary>
public UInt32 last_recovery;
/// <summary> time of last all-clear in milliseconds since boot </summary>
public UInt32 last_clear;
/// <summary> number of fence breaches </summary>
public UInt16 breach_count;
/// <summary> state of AP_Limits, (see enum LimitState, LIMITS_STATE) </summary>
public byte limits_state;
/// <summary> AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) </summary>
public byte mods_enabled;
/// <summary> AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) </summary>
public byte mods_required;
/// <summary> AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) </summary>
public byte mods_triggered;
};
public const byte MAVLINK_MSG_ID_HEARTBEAT = 0;
[StructLayout(LayoutKind.Sequential,Pack=1,Size=9)]
public struct mavlink_heartbeat_t
@ -1859,6 +1925,48 @@ namespace ArdupilotMega
};
public const byte MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT = 60;
[StructLayout(LayoutKind.Sequential,Pack=1,Size=9)]
public struct mavlink_set_quad_motors_setpoint_t
{
/// <summary> Front motor in + configuration, front left motor in x configuration </summary>
public UInt16 motor_front_nw;
/// <summary> Right motor in + configuration, front right motor in x configuration </summary>
public UInt16 motor_right_ne;
/// <summary> Back motor in + configuration, back right motor in x configuration </summary>
public UInt16 motor_back_se;
/// <summary> Left motor in + configuration, back left motor in x configuration </summary>
public UInt16 motor_left_sw;
/// <summary> System ID of the system that should set these motor commands </summary>
public byte target_system;
};
public const byte MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST = 61;
[StructLayout(LayoutKind.Sequential,Pack=1,Size=34)]
public struct mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t
{
/// <summary> Desired roll angle in radians +-PI (+-32767) </summary>
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
public Int16[] roll;
/// <summary> Desired pitch angle in radians +-PI (+-32767) </summary>
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
public Int16[] pitch;
/// <summary> Desired yaw angle in radians, scaled to int16 +-PI (+-32767) </summary>
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
public Int16[] yaw;
/// <summary> Collective thrust, scaled to uint16 (0..65535) </summary>
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
public UInt16[] thrust;
/// <summary> ID of the quadrotor group (0 - 255, up to 256 groups supported) </summary>
public byte group;
/// <summary> ID of the flight mode (0 - 255, up to 256 modes supported) </summary>
public byte mode;
};
public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62;
[StructLayout(LayoutKind.Sequential,Pack=1,Size=26)]
public struct mavlink_nav_controller_output_t
@ -1883,6 +1991,39 @@ namespace ArdupilotMega
};
public const byte MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST = 63;
[StructLayout(LayoutKind.Sequential,Pack=1,Size=46)]
public struct mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t
{
/// <summary> Desired roll angle in radians +-PI (+-32767) </summary>
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
public Int16[] roll;
/// <summary> Desired pitch angle in radians +-PI (+-32767) </summary>
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
public Int16[] pitch;
/// <summary> Desired yaw angle in radians, scaled to int16 +-PI (+-32767) </summary>
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
public Int16[] yaw;
/// <summary> Collective thrust, scaled to uint16 (0..65535) </summary>
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
public UInt16[] thrust;
/// <summary> ID of the quadrotor group (0 - 255, up to 256 groups supported) </summary>
public byte group;
/// <summary> ID of the flight mode (0 - 255, up to 256 modes supported) </summary>
public byte mode;
/// <summary> RGB red channel (0-255) </summary>
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
public byte[] led_red;
/// <summary> RGB green channel (0-255) </summary>
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
public byte[] led_blue;
/// <summary> RGB blue channel (0-255) </summary>
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
public byte[] led_green;
};
public const byte MAVLINK_MSG_ID_STATE_CORRECTION = 64;
[StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
public struct mavlink_state_correction_t
@ -2057,6 +2198,28 @@ namespace ArdupilotMega
};
public const byte MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89;
[StructLayout(LayoutKind.Sequential,Pack=1,Size=28)]
public struct mavlink_local_position_ned_system_global_offset_t
{
/// <summary> Timestamp (milliseconds since system boot) </summary>
public UInt32 time_boot_ms;
/// <summary> X Position </summary>
public Single x;
/// <summary> Y Position </summary>
public Single y;
/// <summary> Z Position </summary>
public Single z;
/// <summary> Roll </summary>
public Single roll;
/// <summary> Pitch </summary>
public Single pitch;
/// <summary> Yaw </summary>
public Single yaw;
};
public const byte MAVLINK_MSG_ID_HIL_STATE = 90;
[StructLayout(LayoutKind.Sequential,Pack=1,Size=56)]
public struct mavlink_hil_state_t
@ -2164,12 +2327,16 @@ namespace ArdupilotMega
public const byte MAVLINK_MSG_ID_OPTICAL_FLOW = 100;
[StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
[StructLayout(LayoutKind.Sequential,Pack=1,Size=26)]
public struct mavlink_optical_flow_t
{
/// <summary> Timestamp (UNIX) </summary>
public UInt64 time_usec;
/// <summary> Ground distance in meters </summary>
/// <summary> Flow in meters in x-sensor direction, angular-speed compensated </summary>
public Single flow_comp_m_x;
/// <summary> Flow in meters in y-sensor direction, angular-speed compensated </summary>
public Single flow_comp_m_y;
/// <summary> Ground distance in meters. Positive value: distance known. Negative value: Unknown distance </summary>
public Single ground_distance;
/// <summary> Flow in pixels in x-sensor direction </summary>
public Int16 flow_x;
@ -2355,22 +2522,8 @@ namespace ArdupilotMega
/// <summary> index of debug variable </summary>
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
{
/// <summary> System which should execute the command </summary>
public byte target_system;
/// <summary> Component which should execute the command, 0 for all components </summary>
public byte target_component;
/// <summary> Retransmission / ACK flags </summary>
public byte protocol_flags;
};
}
#endif
#endif
}

View File

@ -2,14 +2,14 @@
<Wix xmlns="http://schemas.microsoft.com/wix/2006/wi" xmlns:netfx="http://schemas.microsoft.com/wix/NetFxExtension" xmlns:difx="http://schemas.microsoft.com/wix/DifxAppExtension">
<Product Id="*" Name="APM Planner" Language="1033" Version="1.1.99" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
<Product Id="*" Name="APM Planner" Language="1033" Version="1.2" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
<Package Description="APM Planner Installer" Comments="Apm Planner Installer" Manufacturer="Michael Oborne" InstallerVersion="200" Compressed="yes" />
<Upgrade Id="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
<UpgradeVersion OnlyDetect="yes" Minimum="1.1.99" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" />
<UpgradeVersion OnlyDetect="no" Maximum="1.1.99" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" />
<UpgradeVersion OnlyDetect="yes" Minimum="1.2" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" />
<UpgradeVersion OnlyDetect="no" Maximum="1.2" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" />
</Upgrade>
<InstallExecuteSequence>
@ -31,7 +31,7 @@
<Permission User="Everyone" GenericAll="yes" />
</CreateFolder>
</Component>
<Component Id="_comp1" Guid="cfe0ddd0-0732-4beb-8a9e-0689155a8ff7">
<Component Id="_comp1" Guid="6426307e-9832-4641-a69f-fef6e731ae94">
<File Id="_2" Source="..\bin\release\.gdbinit" />
<File Id="_3" Source="..\bin\release\.gitignore" />
<File Id="_4" Source="..\bin\release\aerosim3.91.txt" />
@ -107,11 +107,11 @@
<File Id="_74" Source="..\bin\release\ZedGraph.dll" />
</Component>
<Directory Id="aircraft74" Name="aircraft">
<Component Id="_comp75" Guid="31348cb7-5b6e-49d9-a7a9-09c767f9116e">
<Component Id="_comp75" Guid="aca211c5-59ca-42bb-b587-2ce9101e641d">
<File Id="_76" Source="..\bin\release\aircraft\placeholder.txt" />
</Component>
<Directory Id="arducopter76" Name="arducopter">
<Component Id="_comp77" Guid="53ee8643-5f00-48ea-b8db-eb92e8e01255">
<Component Id="_comp77" Guid="d56d69fa-8119-46d6-85ae-8d8faee8d3ea">
<File Id="_78" Source="..\bin\release\aircraft\arducopter\arducopter-set.xml" />
<File Id="_79" Source="..\bin\release\aircraft\arducopter\arducopter.jpg" />
<File Id="_80" Source="..\bin\release\aircraft\arducopter\arducopter.xml" />
@ -122,20 +122,20 @@
<File Id="_85" Source="..\bin\release\aircraft\arducopter\README" />
</Component>
<Directory Id="data85" Name="data">
<Component Id="_comp86" Guid="34d12f92-99d7-4698-bba4-ba3e99205d1e">
<Component Id="_comp86" Guid="f9bee73e-2642-4bd2-bcaa-85b2d2881099">
<File Id="_87" Source="..\bin\release\aircraft\arducopter\data\arducopter_half_step.txt" />
<File Id="_88" Source="..\bin\release\aircraft\arducopter\data\arducopter_step.txt" />
<File Id="_89" Source="..\bin\release\aircraft\arducopter\data\rw_generic_pylon.ac" />
</Component>
</Directory>
<Directory Id="Engines89" Name="Engines">
<Component Id="_comp90" Guid="db243c75-5c96-4730-9c7e-4e1197d5bd3b">
<Component Id="_comp90" Guid="6a518147-28f8-45dc-9ba1-68fc0dbf09cb">
<File Id="_91" Source="..\bin\release\aircraft\arducopter\Engines\a2830-12.xml" />
<File Id="_92" Source="..\bin\release\aircraft\arducopter\Engines\prop10x4.5.xml" />
</Component>
</Directory>
<Directory Id="Models92" Name="Models">
<Component Id="_comp93" Guid="641c20ea-69a2-4964-be35-4e359192ede0">
<Component Id="_comp93" Guid="da9fc9ee-19a1-42eb-b950-800c3a887a78">
<File Id="_94" Source="..\bin\release\aircraft\arducopter\Models\arducopter.ac" />
<File Id="_95" Source="..\bin\release\aircraft\arducopter\Models\arducopter.xml" />
<File Id="_96" Source="..\bin\release\aircraft\arducopter\Models\plus_quad.ac" />
@ -149,7 +149,7 @@
</Directory>
</Directory>
<Directory Id="Rascal102" Name="Rascal">
<Component Id="_comp103" Guid="668ed46e-d67f-4d7b-8492-3b9cbd8bde52">
<Component Id="_comp103" Guid="8103cc9f-8018-4340-b094-22670c86bb39">
<File Id="_104" Source="..\bin\release\aircraft\Rascal\Rascal-keyboard.xml" />
<File Id="_105" Source="..\bin\release\aircraft\Rascal\Rascal-submodels.xml" />
<File Id="_106" Source="..\bin\release\aircraft\Rascal\Rascal.xml" />
@ -161,13 +161,13 @@
<File Id="_112" Source="..\bin\release\aircraft\Rascal\thumbnail.jpg" />
</Component>
<Directory Id="Engines112" Name="Engines">
<Component Id="_comp113" Guid="10bf9f82-c138-4be0-9e6f-5408b93b6634">
<Component Id="_comp113" Guid="5b4c5058-bcbe-4c41-8777-4290a3a18545">
<File Id="_114" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml" />
<File Id="_115" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml" />
</Component>
</Directory>
<Directory Id="Models115" Name="Models">
<Component Id="_comp116" Guid="d677c1f6-7108-4095-a509-07f0c7cd27a9">
<Component Id="_comp116" Guid="0a4643af-1a69-4da5-a43d-27fdf4ec151c">
<File Id="_117" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb" />
<File Id="_118" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac" />
<File Id="_119" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml" />
@ -178,7 +178,7 @@
</Component>
</Directory>
<Directory Id="Systems123" Name="Systems">
<Component Id="_comp124" Guid="f73b8966-b593-44a9-b1f0-82c36e8474a5">
<Component Id="_comp124" Guid="8aec08aa-b972-47ee-b8cd-c5c04b07c6fc">
<File Id="_125" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml" />
<File Id="_126" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas" />
<File Id="_127" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml" />
@ -189,33 +189,33 @@
</Directory>
</Directory>
<Directory Id="Driver129" Name="Driver">
<Component Id="_comp130" Guid="17cacd75-bc0d-4c98-8f0e-6016448f51d2">
<Component Id="_comp130" Guid="c36be0ee-37f5-4de9-a2bf-713833a6e9f1">
<File Id="_131" Source="..\bin\release\Driver\Arduino MEGA 2560.inf" />
</Component>
</Directory>
<Directory Id="es_ES131" Name="es-ES">
<Component Id="_comp132" Guid="a6be862c-fe38-42e7-bce8-bbeef46055d9">
<Component Id="_comp132" Guid="732f43ab-6645-4c18-a1f1-9519ef92165a">
<File Id="_133" Source="..\bin\release\es-ES\ArdupilotMegaPlanner10.resources.dll" />
</Component>
</Directory>
<Directory Id="fr133" Name="fr">
<Component Id="_comp134" Guid="c8b975d0-c6be-4859-838f-1a45412f7e7b">
<Component Id="_comp134" Guid="098a3485-f089-45a6-abd3-442d9818423c">
<File Id="_135" Source="..\bin\release\fr\ArdupilotMegaPlanner10.resources.dll" />
</Component>
</Directory>
<Directory Id="it_IT135" Name="it-IT">
<Component Id="_comp136" Guid="ccd50732-a513-4593-b95e-2d960c545def">
<Component Id="_comp136" Guid="299d4a51-3c5d-44da-9aaa-a298ec1c7d28">
<File Id="_137" Source="..\bin\release\it-IT\ArdupilotMegaPlanner10.resources.dll" />
</Component>
</Directory>
<Directory Id="jsbsim137" Name="jsbsim">
<Component Id="_comp138" Guid="347a2191-8ccf-48b8-8c73-a9e2dfaa7324">
<Component Id="_comp138" Guid="65b5860e-5296-41f2-90cc-cdbc5f8c82d1">
<File Id="_139" Source="..\bin\release\jsbsim\fgout.xml" />
<File Id="_140" Source="..\bin\release\jsbsim\rascal_test.xml" />
</Component>
</Directory>
<Directory Id="m3u140" Name="m3u">
<Component Id="_comp141" Guid="418006de-8353-4876-98bd-1b89676e5856">
<Component Id="_comp141" Guid="2c669359-f253-406a-b60d-84312ebcdbc7">
<File Id="_142" Source="..\bin\release\m3u\both.m3u" />
<File Id="_143" Source="..\bin\release\m3u\GeoRefnetworklink.kml" />
<File Id="_144" Source="..\bin\release\m3u\hud.m3u" />
@ -224,28 +224,28 @@
</Component>
</Directory>
<Directory Id="pl146" Name="pl">
<Component Id="_comp147" Guid="02fa2a0c-1fb1-4481-9fb7-f16e4e2ee698">
<Component Id="_comp147" Guid="ddb9853c-14d0-4923-a298-57707bfa3e91">
<File Id="_148" Source="..\bin\release\pl\ArdupilotMegaPlanner10.resources.dll" />
</Component>
</Directory>
<Directory Id="Resources148" Name="Resources">
<Component Id="_comp149" Guid="8ca473a7-ef8f-4c28-a9e8-865e92f4dc49">
<Component Id="_comp149" Guid="92c1e1c0-3b2b-4511-a357-6498b3acca4d">
<File Id="_150" Source="..\bin\release\Resources\MAVCmd.txt" />
<File Id="_151" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf" />
</Component>
</Directory>
<Directory Id="ru_RU151" Name="ru-RU">
<Component Id="_comp152" Guid="4de739ef-0a43-4edc-a496-63b5d6fe25c2">
<Component Id="_comp152" Guid="866f909e-fb5f-4fb2-a61e-0d0f6dbebac7">
<File Id="_153" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner10.resources.dll" />
</Component>
</Directory>
<Directory Id="zh_Hans153" Name="zh-Hans">
<Component Id="_comp154" Guid="1604219a-af8e-4bd3-96ba-57475defe074">
<Component Id="_comp154" Guid="c3bbe27c-d473-409e-a406-4cc492a06f8a">
<File Id="_155" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner10.resources.dll" />
</Component>
</Directory>
<Directory Id="zh_TW155" Name="zh-TW">
<Component Id="_comp156" Guid="96a9d78a-2294-4c08-b983-158519cea2b8">
<Component Id="_comp156" Guid="6a93efeb-6489-4ef3-b6b3-26e808adfb8d">
<File Id="_157" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner10.resources.dll" />
</Component>
</Directory>

View File

@ -8,7 +8,6 @@ using System.Threading;
using log4net;
using log4net.Config;
namespace ArdupilotMega
{
static class Program
@ -63,7 +62,6 @@ namespace ArdupilotMega
return;
*/
try
{

View File

@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.1.*")]
[assembly: AssemblyFileVersion("1.2")]
[assembly: AssemblyFileVersion("1.2.1")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -40,11 +40,10 @@
<F4>WP Alt</F4>
<F5>Nav Throttle</F5>
<F6>Angle boost</F6>
<F7>Manual boost</F7>
<F8>Climb Rate</F8>
<F9>rc3 servo out</F9>
<F10>alt hold int</F10>
<F11>Thr int</F11>
<F7>Climb Rate</F7>
<F8>rc3 servo out</F8>
<F9>alt hold int</F9>
<F10>Thr int</F10>
</CTUN>
<PM>
<F1>Gyro Saturation</F1>

View File

@ -66,13 +66,13 @@
<Z>Alt</Z>
</TAKEOFF>
<ROI>
<P1>MAV_ROI</P1>
<P2>WP#</P2>
<P3>ROI#</P3>
<P1></P1>
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</ROI>
<PATHPLANNING>
<P1></P1>
@ -308,9 +308,9 @@
<P2></P2>
<P3></P3>
<P4></P4>
<X></X>
<Y></Y>
<Z></Z>
<X>Lat</X>
<Y>Long</Y>
<Z>Alt</Z>
</ROI>
<PATHPLANNING>
<P1></P1>