mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
APM Planner 1.0.80
add AeroSimRC for HIL - plane/heli/quad
This commit is contained in:
parent
f2fa24375e
commit
26c8f734bf
2
Tools/ArdupilotMegaPlanner/APMPlannerXplanes/.gitignore
vendored
Normal file
2
Tools/ArdupilotMegaPlanner/APMPlannerXplanes/.gitignore
vendored
Normal file
@ -0,0 +1,2 @@
|
|||||||
|
|
||||||
|
*.sdf
|
@ -0,0 +1,38 @@
|
|||||||
|
========================================================================
|
||||||
|
DYNAMIC LINK LIBRARY : APMPlannerXplanes Project Overview
|
||||||
|
========================================================================
|
||||||
|
|
||||||
|
AppWizard has created this APMPlannerXplanes DLL for you.
|
||||||
|
|
||||||
|
This file contains a summary of what you will find in each of the files that
|
||||||
|
make up your APMPlannerXplanes application.
|
||||||
|
|
||||||
|
APMPlannerXplanes.vcxproj
|
||||||
|
This is the main project file for VC++ projects generated using an Application Wizard.
|
||||||
|
It contains information about the version of Visual C++ that generated the file, and
|
||||||
|
information about the platforms, configurations, and project features selected with the
|
||||||
|
Application Wizard.
|
||||||
|
|
||||||
|
APMPlannerXplanes.vcxproj.filters
|
||||||
|
This is the filters file for VC++ projects generated using an Application Wizard.
|
||||||
|
It contains information about the association between the files in your project
|
||||||
|
and the filters. This association is used in the IDE to show grouping of files with
|
||||||
|
similar extensions under a specific node (for e.g. ".cpp" files are associated with the
|
||||||
|
"Source Files" filter).
|
||||||
|
|
||||||
|
APMPlannerXplanes.cpp
|
||||||
|
This is the main DLL source file.
|
||||||
|
|
||||||
|
APMPlannerXplanes.h
|
||||||
|
This file contains a class declaration.
|
||||||
|
|
||||||
|
AssemblyInfo.cpp
|
||||||
|
Contains custom attributes for modifying assembly metadata.
|
||||||
|
|
||||||
|
/////////////////////////////////////////////////////////////////////////////
|
||||||
|
Other notes:
|
||||||
|
|
||||||
|
AppWizard uses "TODO:" to indicate parts of the source code you
|
||||||
|
should add to or customize.
|
||||||
|
|
||||||
|
/////////////////////////////////////////////////////////////////////////////
|
@ -496,6 +496,9 @@
|
|||||||
<EmbeddedResource Include="temp.resx">
|
<EmbeddedResource Include="temp.resx">
|
||||||
<DependentUpon>temp.cs</DependentUpon>
|
<DependentUpon>temp.cs</DependentUpon>
|
||||||
</EmbeddedResource>
|
</EmbeddedResource>
|
||||||
|
<None Include="AeroSimRCAPMHil.zip">
|
||||||
|
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||||
|
</None>
|
||||||
<None Include="app.config" />
|
<None Include="app.config" />
|
||||||
<None Include="arducopter-fgmodel.zip">
|
<None Include="arducopter-fgmodel.zip">
|
||||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||||
|
@ -121,28 +121,28 @@
|
|||||||
<data name="Params.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="Params.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Top, Bottom, Left</value>
|
<value>Top, Bottom, Left</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="Command.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||||
|
<data name="Command.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</metadata>
|
</data>
|
||||||
<data name="Command.HeaderText" xml:space="preserve">
|
<data name="Command.HeaderText" xml:space="preserve">
|
||||||
<value>Command</value>
|
<value>Command</value>
|
||||||
</data>
|
</data>
|
||||||
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
|
||||||
<data name="Command.Width" type="System.Int32, mscorlib">
|
<data name="Command.Width" type="System.Int32, mscorlib">
|
||||||
<value>150</value>
|
<value>150</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="Value.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
<data name="Value.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</metadata>
|
</data>
|
||||||
<data name="Value.HeaderText" xml:space="preserve">
|
<data name="Value.HeaderText" xml:space="preserve">
|
||||||
<value>Value</value>
|
<value>Value</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="Value.Width" type="System.Int32, mscorlib">
|
<data name="Value.Width" type="System.Int32, mscorlib">
|
||||||
<value>80</value>
|
<value>80</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="Default.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
<data name="Default.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</metadata>
|
</data>
|
||||||
<data name="Default.HeaderText" xml:space="preserve">
|
<data name="Default.HeaderText" xml:space="preserve">
|
||||||
<value>Default</value>
|
<value>Default</value>
|
||||||
</data>
|
</data>
|
||||||
@ -155,9 +155,9 @@
|
|||||||
<data name="mavScale.Visible" type="System.Boolean, mscorlib">
|
<data name="mavScale.Visible" type="System.Boolean, mscorlib">
|
||||||
<value>False</value>
|
<value>False</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="RawValue.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
<data name="RawValue.UserAddedColumn" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</metadata>
|
</data>
|
||||||
<data name="RawValue.HeaderText" xml:space="preserve">
|
<data name="RawValue.HeaderText" xml:space="preserve">
|
||||||
<value>RawValue</value>
|
<value>RawValue</value>
|
||||||
</data>
|
</data>
|
||||||
@ -5340,9 +5340,9 @@
|
|||||||
<data name="CHK_GDIPlus.Text" xml:space="preserve">
|
<data name="CHK_GDIPlus.Text" xml:space="preserve">
|
||||||
<value>GDI+ (old type)</value>
|
<value>GDI+ (old type)</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
<data name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>17, 17</value>
|
<value>17, 17</value>
|
||||||
</metadata>
|
</data>
|
||||||
<data name="CHK_GDIPlus.ToolTip" xml:space="preserve">
|
<data name="CHK_GDIPlus.ToolTip" xml:space="preserve">
|
||||||
<value>OpenGL = Disabled
|
<value>OpenGL = Disabled
|
||||||
GDI+ = Enabled</value>
|
GDI+ = Enabled</value>
|
||||||
@ -6803,9 +6803,9 @@ GDI+ = Enabled</value>
|
|||||||
<data name=">>BUT_compare.ZOrder" xml:space="preserve">
|
<data name=">>BUT_compare.ZOrder" xml:space="preserve">
|
||||||
<value>0</value>
|
<value>0</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
<data name="$this.Localizable" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</metadata>
|
</data>
|
||||||
<data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
|
<data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
|
||||||
<value>8, 16</value>
|
<value>8, 16</value>
|
||||||
</data>
|
</data>
|
||||||
@ -6857,4 +6857,7 @@ GDI+ = Enabled</value>
|
|||||||
<data name=">>$this.Type" xml:space="preserve">
|
<data name=">>$this.Type" xml:space="preserve">
|
||||||
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="MAVParam" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||||
|
<value>..\Resources\MAVParam.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252</value>
|
||||||
|
</data>
|
||||||
</root>
|
</root>
|
@ -110,6 +110,8 @@
|
|||||||
this.BUT_startfgplane = new ArdupilotMega.MyButton();
|
this.BUT_startfgplane = new ArdupilotMega.MyButton();
|
||||||
this.BUT_startxplane = new ArdupilotMega.MyButton();
|
this.BUT_startxplane = new ArdupilotMega.MyButton();
|
||||||
this.CHK_heli = new System.Windows.Forms.CheckBox();
|
this.CHK_heli = new System.Windows.Forms.CheckBox();
|
||||||
|
this.RAD_aerosimrc = new System.Windows.Forms.RadioButton();
|
||||||
|
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
|
||||||
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
|
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
|
||||||
this.panel1.SuspendLayout();
|
this.panel1.SuspendLayout();
|
||||||
this.panel2.SuspendLayout();
|
this.panel2.SuspendLayout();
|
||||||
@ -243,6 +245,7 @@
|
|||||||
this.RAD_softXplanes.Checked = true;
|
this.RAD_softXplanes.Checked = true;
|
||||||
this.RAD_softXplanes.Name = "RAD_softXplanes";
|
this.RAD_softXplanes.Name = "RAD_softXplanes";
|
||||||
this.RAD_softXplanes.TabStop = true;
|
this.RAD_softXplanes.TabStop = true;
|
||||||
|
this.toolTip1.SetToolTip(this.RAD_softXplanes, resources.GetString("RAD_softXplanes.ToolTip"));
|
||||||
this.RAD_softXplanes.UseVisualStyleBackColor = true;
|
this.RAD_softXplanes.UseVisualStyleBackColor = true;
|
||||||
this.RAD_softXplanes.CheckedChanged += new System.EventHandler(this.RAD_softXplanes_CheckedChanged);
|
this.RAD_softXplanes.CheckedChanged += new System.EventHandler(this.RAD_softXplanes_CheckedChanged);
|
||||||
//
|
//
|
||||||
@ -250,6 +253,7 @@
|
|||||||
//
|
//
|
||||||
resources.ApplyResources(this.RAD_softFlightGear, "RAD_softFlightGear");
|
resources.ApplyResources(this.RAD_softFlightGear, "RAD_softFlightGear");
|
||||||
this.RAD_softFlightGear.Name = "RAD_softFlightGear";
|
this.RAD_softFlightGear.Name = "RAD_softFlightGear";
|
||||||
|
this.toolTip1.SetToolTip(this.RAD_softFlightGear, resources.GetString("RAD_softFlightGear.ToolTip"));
|
||||||
this.RAD_softFlightGear.UseVisualStyleBackColor = true;
|
this.RAD_softFlightGear.UseVisualStyleBackColor = true;
|
||||||
this.RAD_softFlightGear.CheckedChanged += new System.EventHandler(this.RAD_softFlightGear_CheckedChanged);
|
this.RAD_softFlightGear.CheckedChanged += new System.EventHandler(this.RAD_softFlightGear_CheckedChanged);
|
||||||
//
|
//
|
||||||
@ -680,10 +684,19 @@
|
|||||||
this.CHK_heli.Name = "CHK_heli";
|
this.CHK_heli.Name = "CHK_heli";
|
||||||
this.CHK_heli.UseVisualStyleBackColor = true;
|
this.CHK_heli.UseVisualStyleBackColor = true;
|
||||||
//
|
//
|
||||||
|
// RAD_aerosimrc
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.RAD_aerosimrc, "RAD_aerosimrc");
|
||||||
|
this.RAD_aerosimrc.Name = "RAD_aerosimrc";
|
||||||
|
this.toolTip1.SetToolTip(this.RAD_aerosimrc, resources.GetString("RAD_aerosimrc.ToolTip"));
|
||||||
|
this.RAD_aerosimrc.UseVisualStyleBackColor = true;
|
||||||
|
this.RAD_aerosimrc.CheckedChanged += new System.EventHandler(this.RAD_aerosimrc_CheckedChanged);
|
||||||
|
//
|
||||||
// Simulation
|
// Simulation
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this, "$this");
|
resources.ApplyResources(this, "$this");
|
||||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||||
|
this.Controls.Add(this.RAD_aerosimrc);
|
||||||
this.Controls.Add(this.CHK_heli);
|
this.Controls.Add(this.CHK_heli);
|
||||||
this.Controls.Add(this.BUT_startxplane);
|
this.Controls.Add(this.BUT_startxplane);
|
||||||
this.Controls.Add(this.BUT_startfgplane);
|
this.Controls.Add(this.BUT_startfgplane);
|
||||||
@ -714,7 +727,7 @@
|
|||||||
this.Controls.Add(this.CHKREV_pitch);
|
this.Controls.Add(this.CHKREV_pitch);
|
||||||
this.Controls.Add(this.CHKREV_roll);
|
this.Controls.Add(this.CHKREV_roll);
|
||||||
this.Name = "Simulation";
|
this.Name = "Simulation";
|
||||||
this.Load += new System.EventHandler(this.ArdupilotSim_Load);
|
this.Load += new System.EventHandler(this.Simulation_Load);
|
||||||
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
|
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
|
||||||
this.panel1.ResumeLayout(false);
|
this.panel1.ResumeLayout(false);
|
||||||
this.panel2.ResumeLayout(false);
|
this.panel2.ResumeLayout(false);
|
||||||
@ -810,5 +823,7 @@
|
|||||||
private MyButton BUT_startfgplane;
|
private MyButton BUT_startfgplane;
|
||||||
private MyButton BUT_startxplane;
|
private MyButton BUT_startxplane;
|
||||||
private System.Windows.Forms.CheckBox CHK_heli;
|
private System.Windows.Forms.CheckBox CHK_heli;
|
||||||
|
private System.Windows.Forms.RadioButton RAD_aerosimrc;
|
||||||
|
private System.Windows.Forms.ToolTip toolTip1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -23,6 +23,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
UdpClient MavLink;
|
UdpClient MavLink;
|
||||||
Socket SimulatorRECV;
|
Socket SimulatorRECV;
|
||||||
//TcpClient FlightGearSEND;
|
//TcpClient FlightGearSEND;
|
||||||
|
EndPoint Remote = (EndPoint)(new IPEndPoint(IPAddress.Any, 0));
|
||||||
byte[] udpdata = new byte[113 * 9 + 5]; // 113 types - 9 items per type (index+8) + 5 byte header
|
byte[] udpdata = new byte[113 * 9 + 5]; // 113 types - 9 items per type (index+8) + 5 byte header
|
||||||
float[][] DATA = new float[113][];
|
float[][] DATA = new float[113][];
|
||||||
DateTime now = DateTime.Now;
|
DateTime now = DateTime.Now;
|
||||||
@ -76,6 +77,117 @@ namespace ArdupilotMega.GCSViews
|
|||||||
public uint magic;
|
public uint magic;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
const int AEROSIMRC_MAX_CHANNELS = 39;
|
||||||
|
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
// Two main data structures are used. This is the first one:
|
||||||
|
//
|
||||||
|
// This data struct is filled by AeroSIM RC with the simulation data, and sent to the plugin
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
[StructLayout(LayoutKind.Sequential, Pack = 1)]
|
||||||
|
public struct TDataFromAeroSimRC
|
||||||
|
{
|
||||||
|
public ushort nStructSize; // size in bytes of TDataFromAeroSimRC
|
||||||
|
|
||||||
|
//---------------------
|
||||||
|
// Integration Time
|
||||||
|
//---------------------
|
||||||
|
public float Simulation_fIntegrationTimeStep; // integration time step in seconds. This is the simulated time since last call to AeroSIMRC_Plugin_Run()
|
||||||
|
|
||||||
|
//---------------------
|
||||||
|
// Channels
|
||||||
|
//---------------------
|
||||||
|
|
||||||
|
[MarshalAs(
|
||||||
|
UnmanagedType.ByValArray,
|
||||||
|
SizeConst = AEROSIMRC_MAX_CHANNELS)]
|
||||||
|
public float[] Channel_afValue_TX; // [-1, 1] channel positions at TX sticks (i.e. raw stick positions)
|
||||||
|
[MarshalAs(
|
||||||
|
UnmanagedType.ByValArray,
|
||||||
|
SizeConst = AEROSIMRC_MAX_CHANNELS)]
|
||||||
|
public float[] Channel_afValue_RX; // [-1, 1] channel positions at RX (i.e. after TX mixes)
|
||||||
|
|
||||||
|
// Use the following constants as indexes for the channel arrays
|
||||||
|
// The simulator uses internally the channel numbers for Transmitter Mode 2 (regardless of mode selected by user)
|
||||||
|
const int CH_AILERON = 0;
|
||||||
|
const int CH_ELEVATOR = 1;
|
||||||
|
const int CH_THROTTLE = 2;
|
||||||
|
const int CH_RUDDER = 3;
|
||||||
|
const int CH_5 = 4;
|
||||||
|
const int CH_6 = 5;
|
||||||
|
const int CH_7 = 6;
|
||||||
|
const int CH_PLUGIN_1 = 22; // This channel is mapped by user to any real channel number
|
||||||
|
const int CH_PLUGIN_2 = 23; // This channel is mapped by user to any real channel number
|
||||||
|
|
||||||
|
//---------------------
|
||||||
|
// OSD
|
||||||
|
//---------------------
|
||||||
|
// Video buffer for OSD is a bitmap, 4 bytes per pixel: R G B A; The first 4 bytes are the Top-Left corner pixel
|
||||||
|
// The size of the OSD Video Buffer is defined in plugin.txt
|
||||||
|
// .OSD_BUFFER_SIZE, in plugin.txt, can be set to one of the following sizes: 512x512, 1024x512 or 1024x1024
|
||||||
|
// Set OSD_nWindow_DX and OSD_nWindow_DY in struct TDataToAeroSimRC to the actual size to be displayed
|
||||||
|
public IntPtr OSD_pVideoBuffer;
|
||||||
|
|
||||||
|
//---------------------
|
||||||
|
// Menu
|
||||||
|
//---------------------
|
||||||
|
// This variable represent the custom menu status. E.g. 0x000001 means that first menu item is ticked
|
||||||
|
// Command menu item bits are set to 1 when selected, but cleared in the next cycle.
|
||||||
|
// Checkbox menu item bits remain 1 until unchecked by user, or cleared in TDataToAeroSimRC::Menu_nFlags_MenuItem_New_CheckBox_Status
|
||||||
|
public uint Menu_nFlags_MenuItem_Status;
|
||||||
|
|
||||||
|
//---------------------
|
||||||
|
// Model Initial Position in current scenario
|
||||||
|
//---------------------
|
||||||
|
public float Scenario_fInitialModelPosX; public float Scenario_fInitialModelPosY; public float Scenario_fInitialModelPosZ; // (m) Model Initial Position on runway
|
||||||
|
public float Scenario_fInitialModelHeading; public float Scenario_fInitialModelPitch; public float Scenario_fInitialModelRoll; // (m) Model Initial Attitude on runway
|
||||||
|
|
||||||
|
//---------------------
|
||||||
|
// WayPoints
|
||||||
|
// The Description string can be freely used to add more information to the waypoint such as Altitude, WP Type (Overfly, Landing, CAP), Bearing, etc.
|
||||||
|
//---------------------
|
||||||
|
public float Scenario_fWPHome_X; public float Scenario_fWPHome_Y; public float Scenario_fWPHome_Lat; public float Scenario_fWPHome_Long; IntPtr Scenario_strWPHome_Description; // (m, deg, string)
|
||||||
|
public float Scenario_fWPA_X; public float Scenario_fWPA_Y; public float Scenario_fWPA_Lat; public float Scenario_fWPA_Long; IntPtr Scenario_strWPA_Description; // (m, deg, string)
|
||||||
|
public float Scenario_fWPB_X; public float Scenario_fWPB_Y; public float Scenario_fWPB_Lat; public float Scenario_fWPB_Long; IntPtr Scenario_strWPB_Description; // (m, deg, string)
|
||||||
|
public float Scenario_fWPC_X; public float Scenario_fWPC_Y; public float Scenario_fWPC_Lat; public float Scenario_fWPC_Long; IntPtr Scenario_strWPC_Description; // (m, deg, string)
|
||||||
|
public float Scenario_fWPD_X; public float Scenario_fWPD_Y; public float Scenario_fWPD_Lat; public float Scenario_fWPD_Long; IntPtr Scenario_strWPD_Description; // (m, deg, string)
|
||||||
|
|
||||||
|
//---------------------
|
||||||
|
// Model data
|
||||||
|
//---------------------
|
||||||
|
public float Model_fPosX; public float Model_fPosY; public float Model_fPosZ; // m Model absolute position in scenario (X=Right, Y=Front, Z=Up)
|
||||||
|
public float Model_fVelX; public float Model_fVelY; public float Model_fVelZ; // m/s Model velocity
|
||||||
|
public float Model_fAngVelX; public float Model_fAngVelY; public float Model_fAngVelZ; // rad/s Model angular velocity (useful to implement gyroscopes)
|
||||||
|
public float Model_fAccelX; public float Model_fAccelY; public float Model_fAccelZ; // m/s/s Model acceleration (useful to implement accelerometers)
|
||||||
|
|
||||||
|
public double Model_fLatitude; public double Model_fLongitude; // deg Model Position in Lat/Long coordinates
|
||||||
|
|
||||||
|
public float Model_fHeightAboveTerrain; // m
|
||||||
|
|
||||||
|
public float Model_fHeading; // rad [-PI, PI ] 0 = North, PI/2 = East, PI = South, - PI/2 = West
|
||||||
|
public float Model_fPitch; // rad [-PI/2, PI/2] Positive pitch when nose up
|
||||||
|
public float Model_fRoll; // rad [-PI, PI ] Positive roll when right wing Up
|
||||||
|
|
||||||
|
// Wind
|
||||||
|
public float Model_fWindVelX; public float Model_fWindVelY; public float Model_fWindVelZ; // m/s Velocity of the wind (with gusts) at model position (useful to compute air vel)
|
||||||
|
|
||||||
|
// Engine/Motor Revs per minute
|
||||||
|
public float Model_fEngine1_RPM;
|
||||||
|
public float Model_fEngine2_RPM;
|
||||||
|
public float Model_fEngine3_RPM;
|
||||||
|
public float Model_fEngine4_RPM;
|
||||||
|
|
||||||
|
// Battery (electric models)
|
||||||
|
public float Model_fBatteryVoltage; // V
|
||||||
|
public float Model_fBatteryCurrent; // A
|
||||||
|
public float Model_fBatteryConsumedCharge; // Ah
|
||||||
|
public float Model_fBatteryCapacity; // Ah
|
||||||
|
|
||||||
|
// Fuel (gas & jet models)
|
||||||
|
public float Model_fFuelConsumed; // l
|
||||||
|
public float Model_fFuelTankCapacity; // l
|
||||||
|
};
|
||||||
|
|
||||||
~Simulation()
|
~Simulation()
|
||||||
{
|
{
|
||||||
if (threadrun == 1)
|
if (threadrun == 1)
|
||||||
@ -89,11 +201,9 @@ namespace ArdupilotMega.GCSViews
|
|||||||
public Simulation()
|
public Simulation()
|
||||||
{
|
{
|
||||||
InitializeComponent();
|
InitializeComponent();
|
||||||
|
|
||||||
//Control.CheckForIllegalCrossThreadCalls = false; // so can update display from another thread
|
|
||||||
}
|
}
|
||||||
|
|
||||||
private void ArdupilotSim_Load(object sender, EventArgs e)
|
private void Simulation_Load(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
GPSrate.SelectedIndex = 2;
|
GPSrate.SelectedIndex = 2;
|
||||||
|
|
||||||
@ -169,8 +279,8 @@ namespace ArdupilotMega.GCSViews
|
|||||||
if (XplanesSEND != null)
|
if (XplanesSEND != null)
|
||||||
XplanesSEND.Close();
|
XplanesSEND.Close();
|
||||||
|
|
||||||
// if (comPort.BaseStream.IsOpen)
|
// if (comPort.BaseStream.IsOpen)
|
||||||
// comPort.stopall(true);
|
// comPort.stopall(true);
|
||||||
|
|
||||||
OutputLog.AppendText("Sim Link Stopped\n");
|
OutputLog.AppendText("Sim Link Stopped\n");
|
||||||
|
|
||||||
@ -379,7 +489,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
|
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
|
||||||
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
|
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
|
||||||
threadrun = 1;
|
threadrun = 1;
|
||||||
EndPoint Remote = (EndPoint)(new IPEndPoint(IPAddress.Any, 0));
|
Remote = (EndPoint)(new IPEndPoint(IPAddress.Any, 0));
|
||||||
|
|
||||||
DateTime lastdata = DateTime.MinValue;
|
DateTime lastdata = DateTime.MinValue;
|
||||||
|
|
||||||
@ -449,7 +559,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
|
|
||||||
if (hzcounttime.Second != DateTime.Now.Second)
|
if (hzcounttime.Second != DateTime.Now.Second)
|
||||||
{
|
{
|
||||||
// Console.WriteLine("SIM hz {0}", hzcount);
|
// Console.WriteLine("SIM hz {0}", hzcount);
|
||||||
hzcount = 0;
|
hzcount = 0;
|
||||||
hzcounttime = DateTime.Now;
|
hzcounttime = DateTime.Now;
|
||||||
}
|
}
|
||||||
@ -476,7 +586,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
|
|
||||||
SimulatorRECV.Bind(ipep);
|
SimulatorRECV.Bind(ipep);
|
||||||
|
|
||||||
OutputLog.AppendText("Listerning on port "+recvPort+" (sim->planner)\n");
|
OutputLog.AppendText("Listerning on port " + recvPort + " (sim->planner)\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
private void SetupUDPXplanes()
|
private void SetupUDPXplanes()
|
||||||
@ -484,7 +594,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
// setup sender
|
// setup sender
|
||||||
XplanesSEND = new UdpClient(simIP, simPort);
|
XplanesSEND = new UdpClient(simIP, simPort);
|
||||||
|
|
||||||
OutputLog.AppendText("Sending to port "+simPort+" (planner->sim)\n");
|
OutputLog.AppendText("Sending to port " + simPort + " (planner->sim)\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
private void SetupUDPMavLink()
|
private void SetupUDPMavLink()
|
||||||
@ -624,14 +734,14 @@ namespace ArdupilotMega.GCSViews
|
|||||||
att.pitchspeed = (DATA[17][0]);
|
att.pitchspeed = (DATA[17][0]);
|
||||||
att.rollspeed = (DATA[17][1]);
|
att.rollspeed = (DATA[17][1]);
|
||||||
att.yawspeed = (DATA[17][2]);
|
att.yawspeed = (DATA[17][2]);
|
||||||
|
|
||||||
TimeSpan timediff = DateTime.Now - oldtime;
|
TimeSpan timediff = DateTime.Now - oldtime;
|
||||||
|
|
||||||
float pdiff = (float)((att.pitch - oldatt.pitch) / timediff.TotalSeconds);
|
float pdiff = (float)((att.pitch - oldatt.pitch) / timediff.TotalSeconds);
|
||||||
float rdiff = (float)((att.roll - oldatt.roll) / timediff.TotalSeconds);
|
float rdiff = (float)((att.roll - oldatt.roll) / timediff.TotalSeconds);
|
||||||
float ydiff = (float)((att.yaw - oldatt.yaw) / timediff.TotalSeconds);
|
float ydiff = (float)((att.yaw - oldatt.yaw) / timediff.TotalSeconds);
|
||||||
|
|
||||||
// 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]);
|
// 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]);
|
||||||
|
|
||||||
oldatt = att;
|
oldatt = att;
|
||||||
|
|
||||||
@ -724,6 +834,46 @@ namespace ArdupilotMega.GCSViews
|
|||||||
//stream.Write(data, 0, receviedbytes);
|
//stream.Write(data, 0, receviedbytes);
|
||||||
//stream.Close();
|
//stream.Close();
|
||||||
}
|
}
|
||||||
|
else if (receviedbytes == 582)
|
||||||
|
{
|
||||||
|
TDataFromAeroSimRC aeroin = new TDataFromAeroSimRC();
|
||||||
|
|
||||||
|
object temp = aeroin;
|
||||||
|
|
||||||
|
MAVLink.ByteArrayToStructure(data, ref temp, 0);
|
||||||
|
|
||||||
|
aeroin = (TDataFromAeroSimRC)(temp);
|
||||||
|
|
||||||
|
att.pitch = (aeroin.Model_fPitch);
|
||||||
|
att.roll = (aeroin.Model_fRoll * -1);
|
||||||
|
att.yaw = (float)((aeroin.Model_fHeading));
|
||||||
|
att.pitchspeed = (aeroin.Model_fAngVelX);
|
||||||
|
att.rollspeed = (aeroin.Model_fAngVelY);
|
||||||
|
att.yawspeed = (aeroin.Model_fAngVelZ);
|
||||||
|
|
||||||
|
|
||||||
|
imu.usec = ((ulong)DateTime.Now.ToBinary());
|
||||||
|
imu.xgyro = (short)(aeroin.Model_fAngVelX * 1000); // roll - yes
|
||||||
|
//imu.xmag = (short)(Math.Sin(head * deg2rad) * 1000);
|
||||||
|
imu.ygyro = (short)(aeroin.Model_fAngVelY * 1000); // pitch - yes
|
||||||
|
//imu.ymag = (short)(Math.Cos(head * deg2rad) * 1000);
|
||||||
|
imu.zgyro = (short)(aeroin.Model_fAngVelZ * 1000);
|
||||||
|
//imu.zmag = 0;
|
||||||
|
|
||||||
|
imu.xacc = (Int16)(aeroin.Model_fAccelX * 1000); // pitch
|
||||||
|
imu.yacc = (Int16)(aeroin.Model_fAccelY * 1000); // roll
|
||||||
|
imu.zacc = (Int16)(aeroin.Model_fAccelZ * 1000);
|
||||||
|
|
||||||
|
|
||||||
|
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)));
|
||||||
|
|
||||||
|
}
|
||||||
else if (receviedbytes > 0x100)
|
else if (receviedbytes > 0x100)
|
||||||
{
|
{
|
||||||
|
|
||||||
@ -871,49 +1021,58 @@ namespace ArdupilotMega.GCSViews
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
const int X25_INIT_CRC = 0xffff;
|
|
||||||
const int X25_VALIDATE_CRC = 0xf0b8;
|
|
||||||
|
|
||||||
ushort crc_accumulate(byte b, ushort crc)
|
|
||||||
{
|
|
||||||
unchecked
|
|
||||||
{
|
|
||||||
byte ch = (byte)(b ^ (byte)(crc & 0x00ff));
|
|
||||||
ch = (byte)(ch ^ (ch << 4));
|
|
||||||
return (ushort)((crc >> 8) ^ (ch << 8) ^ (ch << 3) ^ (ch >> 4));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
ushort crc_calculate(byte[] pBuffer, int length)
|
|
||||||
{
|
|
||||||
|
|
||||||
// For a "message" of length bytes contained in the unsigned char array
|
|
||||||
// pointed to by pBuffer, calculate the CRC
|
|
||||||
// crcCalculate(unsigned char* pBuffer, int length, unsigned short* checkConst) < not needed
|
|
||||||
|
|
||||||
ushort crcTmp;
|
|
||||||
int i;
|
|
||||||
|
|
||||||
crcTmp = X25_INIT_CRC;
|
|
||||||
|
|
||||||
for (i = 1; i < length; i++) // skips header U
|
|
||||||
{
|
|
||||||
crcTmp = crc_accumulate(pBuffer[i], crcTmp);
|
|
||||||
//Console.WriteLine(crcTmp + " " + pBuffer[i] + " " + length);
|
|
||||||
}
|
|
||||||
|
|
||||||
return (crcTmp);
|
|
||||||
}
|
|
||||||
|
|
||||||
HIL.QuadCopter quad = new HIL.QuadCopter();
|
HIL.QuadCopter quad = new HIL.QuadCopter();
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
///
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="lat">rads </param>
|
||||||
|
/// <param name="lng">rads </param>
|
||||||
|
/// <param name="alt">m</param>
|
||||||
|
/// <param name="roll">rads</param>
|
||||||
|
/// <param name="pitch">rads</param>
|
||||||
|
/// <param name="heading">rads</param>
|
||||||
|
/// <param name="yaw">rads</param>
|
||||||
|
/// <param name="roll_out">-1 to 1</param>
|
||||||
|
/// <param name="pitch_out">-1 to 1</param>
|
||||||
|
/// <param name="rudder_out">-1 to 1</param>
|
||||||
|
/// <param name="throttle_out">0 to 1</param>
|
||||||
|
private void updateScreenDisplay(double lat,double lng,double alt,double roll,double pitch,double heading, double yaw,double roll_out,double pitch_out, double rudder_out, double throttle_out)
|
||||||
|
{
|
||||||
|
try
|
||||||
|
{
|
||||||
|
// Update Sim stuff
|
||||||
|
this.Invoke((MethodInvoker)delegate
|
||||||
|
{
|
||||||
|
TXT_servoroll.Text = roll_out.ToString("0.000");
|
||||||
|
TXT_servopitch.Text = pitch_out.ToString("0.000");
|
||||||
|
TXT_servorudder.Text = rudder_out.ToString("0.000");
|
||||||
|
TXT_servothrottle.Text = throttle_out.ToString("0.000");
|
||||||
|
|
||||||
|
TXT_lat.Text = (lat * rad2deg).ToString("0.00000");
|
||||||
|
TXT_long.Text = (lng * rad2deg).ToString("0.00000");
|
||||||
|
TXT_alt.Text = (alt).ToString("0.00");
|
||||||
|
|
||||||
|
TXT_roll.Text = (roll * rad2deg).ToString("0.000");
|
||||||
|
TXT_pitch.Text = (pitch * rad2deg).ToString("0.000");
|
||||||
|
TXT_heading.Text = (heading * rad2deg).ToString("0.000");
|
||||||
|
TXT_yaw.Text = (yaw * rad2deg).ToString("0.000");
|
||||||
|
|
||||||
|
TXT_wpdist.Text = MainV2.cs.wp_dist.ToString();
|
||||||
|
TXT_bererror.Text = MainV2.cs.ber_error.ToString();
|
||||||
|
TXT_alterror.Text = MainV2.cs.alt_error.ToString();
|
||||||
|
TXT_WP.Text = MainV2.cs.wpno.ToString();
|
||||||
|
TXT_control_mode.Text = MainV2.cs.mode;
|
||||||
|
});
|
||||||
|
}
|
||||||
|
catch { this.Invoke((MethodInvoker)delegate { OutputLog.AppendText("NO SIM data - exep\n"); }); }
|
||||||
|
}
|
||||||
|
|
||||||
private void processArduPilot()
|
private void processArduPilot()
|
||||||
{
|
{
|
||||||
|
|
||||||
bool heli = CHK_heli.Checked;
|
bool heli = CHK_heli.Checked;
|
||||||
|
|
||||||
// Console.WriteLine("sim "+DateTime.Now.Millisecond);
|
|
||||||
|
|
||||||
if (CHK_quad.Checked)
|
if (CHK_quad.Checked)
|
||||||
{
|
{
|
||||||
|
|
||||||
@ -955,9 +1114,6 @@ namespace ArdupilotMega.GCSViews
|
|||||||
Array.Copy(BitConverter.GetBytes((double)(quad.pitch)), 0, FlightGear, 72, 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.yaw)), 0, FlightGear, 80, 8);
|
||||||
|
|
||||||
|
|
||||||
//Array.Copy(BitConverter.GetBytes(0xc465414d), 0, FlightGear, 88, 4);
|
|
||||||
|
|
||||||
if (RAD_softFlightGear.Checked)
|
if (RAD_softFlightGear.Checked)
|
||||||
{
|
{
|
||||||
|
|
||||||
@ -975,42 +1131,13 @@ namespace ArdupilotMega.GCSViews
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
//Array.Reverse(FlightGear, 88, 4);
|
|
||||||
|
|
||||||
// old style
|
|
||||||
//string send = "3," + (roll_out * REV_roll).ToString(new System.Globalization.CultureInfo("en-US")) + "," + (pitch_out * REV_pitch * -1).ToString(new System.Globalization.CultureInfo("en-US")) + "," + (rudder_out * REV_rudder).ToString(new System.Globalization.CultureInfo("en-US")) + "," + (throttle_out).ToString(new System.Globalization.CultureInfo("en-US")) + "\r\n";
|
|
||||||
|
|
||||||
//FlightGear = new System.Text.ASCIIEncoding().GetBytes(send);
|
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
XplanesSEND.Send(FlightGear, FlightGear.Length);
|
XplanesSEND.Send(FlightGear, FlightGear.Length);
|
||||||
}
|
}
|
||||||
catch (Exception) { Console.WriteLine("Socket Write failed, FG closed?"); }
|
catch (Exception) { Console.WriteLine("Socket Write failed, FG closed?"); }
|
||||||
|
|
||||||
try
|
updateScreenDisplay(lastfdmdata.latitude,lastfdmdata.longitude,lastfdmdata.altitude * .3048,lastfdmdata.phi,lastfdmdata.theta,lastfdmdata.psi,lastfdmdata.psi,m[0],m[1],m[2],m[3]);
|
||||||
{
|
|
||||||
|
|
||||||
// Update Sim stuff
|
|
||||||
this.Invoke((MethodInvoker)delegate
|
|
||||||
{
|
|
||||||
TXT_lat.Text = (lastfdmdata.latitude * rad2deg).ToString("0.00000");
|
|
||||||
TXT_long.Text =(lastfdmdata.longitude * rad2deg).ToString("0.00000");
|
|
||||||
TXT_alt.Text = (lastfdmdata.altitude * .3048).ToString("0.00");
|
|
||||||
|
|
||||||
TXT_roll.Text = (lastfdmdata.phi * rad2deg).ToString("0.000");
|
|
||||||
TXT_pitch.Text =(lastfdmdata.theta * rad2deg).ToString("0.000");
|
|
||||||
TXT_heading.Text = (lastfdmdata.psi * rad2deg).ToString("0.000");
|
|
||||||
TXT_yaw.Text = (lastfdmdata.psi * rad2deg).ToString("0.000");
|
|
||||||
|
|
||||||
TXT_wpdist.Text = MainV2.cs.wp_dist.ToString();
|
|
||||||
TXT_bererror.Text = MainV2.cs.ber_error.ToString();
|
|
||||||
TXT_alterror.Text = MainV2.cs.alt_error.ToString();
|
|
||||||
TXT_WP.Text = MainV2.cs.wpno.ToString();
|
|
||||||
TXT_control_mode.Text = MainV2.cs.mode;
|
|
||||||
});
|
|
||||||
}
|
|
||||||
catch { this.Invoke((MethodInvoker)delegate { OutputLog.AppendText("NO SIM data - exep\n"); }); }
|
|
||||||
|
|
||||||
return;
|
return;
|
||||||
|
|
||||||
@ -1027,7 +1154,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
throttle_out = 1;
|
throttle_out = 1;
|
||||||
rudder_out = (float)MainV2.cs.hilch4 / -ruddergain;
|
rudder_out = (float)MainV2.cs.hilch4 / -ruddergain;
|
||||||
|
|
||||||
collective_out = (float)(MainV2.cs.hilch3 - 1000) / throttlegain;
|
collective_out = (float)(MainV2.cs.hilch3 - 1000) / throttlegain;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
@ -1087,73 +1214,41 @@ namespace ArdupilotMega.GCSViews
|
|||||||
|
|
||||||
if (packetssent % 10 == 0) // reduce cpu usage
|
if (packetssent % 10 == 0) // reduce cpu usage
|
||||||
{
|
{
|
||||||
try
|
if (RAD_softXplanes.Checked)
|
||||||
{
|
{
|
||||||
// update APM stuff
|
updateScreenDisplay(DATA[20][0] * deg2rad, DATA[20][1] * deg2rad, DATA[20][2] * .3048, DATA[18][1] * deg2rad, DATA[18][0] * deg2rad, DATA[19][2] * deg2rad, DATA[18][2] * deg2rad, roll_out, pitch_out, rudder_out, throttle_out);
|
||||||
this.Invoke((MethodInvoker)delegate
|
|
||||||
{
|
|
||||||
TXT_servoroll.Text = roll_out.ToString("0.000");
|
|
||||||
TXT_servopitch.Text = pitch_out.ToString("0.000");
|
|
||||||
TXT_servorudder.Text = rudder_out.ToString("0.000");
|
|
||||||
TXT_servothrottle.Text = throttle_out.ToString("0.000");
|
|
||||||
|
|
||||||
TXT_wpdist.Text = MainV2.cs.wp_dist.ToString();
|
|
||||||
TXT_bererror.Text = MainV2.cs.ber_error.ToString();
|
|
||||||
TXT_alterror.Text = MainV2.cs.alt_error.ToString();
|
|
||||||
TXT_WP.Text = MainV2.cs.wpno.ToString();
|
|
||||||
TXT_control_mode.Text = MainV2.cs.mode;
|
|
||||||
});
|
|
||||||
}
|
}
|
||||||
catch { this.Invoke((MethodInvoker)delegate { OutputLog.AppendText("BAD APM data\n"); }); }
|
|
||||||
try
|
if (RAD_softFlightGear.Checked)
|
||||||
{
|
{
|
||||||
|
updateScreenDisplay(lastfdmdata.latitude, lastfdmdata.longitude, lastfdmdata.altitude * .3048, lastfdmdata.phi, lastfdmdata.theta, lastfdmdata.psi, lastfdmdata.psi, roll_out, pitch_out, rudder_out, throttle_out);
|
||||||
if (DATA[20] != null)
|
|
||||||
{
|
|
||||||
// Update Sim stuff
|
|
||||||
this.Invoke((MethodInvoker)delegate
|
|
||||||
{
|
|
||||||
TXT_lat.Text = DATA[20][0].ToString("0.00000");
|
|
||||||
TXT_long.Text = DATA[20][1].ToString("0.00000");
|
|
||||||
TXT_alt.Text = (DATA[20][2] * .3048).ToString("0.00");
|
|
||||||
|
|
||||||
TXT_roll.Text = DATA[18][1].ToString("0.000");
|
|
||||||
TXT_pitch.Text = DATA[18][0].ToString("0.000");
|
|
||||||
TXT_heading.Text = DATA[19][2].ToString("0.000");
|
|
||||||
TXT_yaw.Text = DATA[18][2].ToString("0.000");
|
|
||||||
});
|
|
||||||
}
|
|
||||||
else if (RAD_softFlightGear.Checked)
|
|
||||||
{
|
|
||||||
TXT_lat.Text = (lastfdmdata.latitude * rad2deg).ToString("0.00000");
|
|
||||||
TXT_long.Text = (lastfdmdata.longitude * rad2deg).ToString("0.00000");
|
|
||||||
TXT_alt.Text = (lastfdmdata.altitude * .3048).ToString("0.00");
|
|
||||||
|
|
||||||
TXT_roll.Text = (lastfdmdata.phi * rad2deg).ToString("0.000");
|
|
||||||
TXT_pitch.Text = (lastfdmdata.theta * rad2deg).ToString("0.000");
|
|
||||||
TXT_heading.Text = (lastfdmdata.psi * rad2deg).ToString("0.000");
|
|
||||||
TXT_yaw.Text = (lastfdmdata.psi * rad2deg).ToString("0.000");
|
|
||||||
|
|
||||||
TXT_wpdist.Text = MainV2.cs.wp_dist.ToString();
|
|
||||||
TXT_bererror.Text = MainV2.cs.ber_error.ToString();
|
|
||||||
TXT_alterror.Text = MainV2.cs.alt_error.ToString();
|
|
||||||
TXT_WP.Text = MainV2.cs.wpno.ToString();
|
|
||||||
TXT_control_mode.Text = MainV2.cs.mode;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
this.Invoke((MethodInvoker)delegate { OutputLog.AppendText(DateTime.Now.ToString("hh:mm:ss") + " NO SIM data - 20\n"); });
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
catch { this.Invoke((MethodInvoker)delegate { OutputLog.AppendText("NO SIM data - exep\n"); }); }
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch (Exception e) { Console.WriteLine("Error updateing screen stuff " + e.ToString()); }
|
catch (Exception e) { Console.WriteLine("Error updateing screen stuff " + e.ToString()); }
|
||||||
|
|
||||||
// Flightgear
|
|
||||||
|
|
||||||
packetssent++;
|
packetssent++;
|
||||||
|
|
||||||
|
if (RAD_aerosimrc.Checked)
|
||||||
|
{
|
||||||
|
//AeroSimRC
|
||||||
|
byte[] AeroSimRC = new byte[4 * 8];// StructureToByteArray(fg);
|
||||||
|
|
||||||
|
Array.Copy(BitConverter.GetBytes((double)(roll_out * REV_roll)), 0, AeroSimRC, 0, 8);
|
||||||
|
Array.Copy(BitConverter.GetBytes((double)(pitch_out * REV_pitch * -1)), 0, AeroSimRC, 8, 8);
|
||||||
|
Array.Copy(BitConverter.GetBytes((double)(rudder_out * REV_rudder)), 0, AeroSimRC, 16, 8);
|
||||||
|
Array.Copy(BitConverter.GetBytes((double)(throttle_out)), 0, AeroSimRC, 24, 8);
|
||||||
|
|
||||||
|
try
|
||||||
|
{
|
||||||
|
SimulatorRECV.SendTo(AeroSimRC, Remote);
|
||||||
|
}
|
||||||
|
catch { }
|
||||||
|
}
|
||||||
|
|
||||||
|
// Flightgear
|
||||||
|
|
||||||
if (RAD_softFlightGear.Checked)
|
if (RAD_softFlightGear.Checked)
|
||||||
{
|
{
|
||||||
//if (packetssent % 2 == 0) { return; } // short supply buffer.. seems to reduce lag
|
//if (packetssent % 2 == 0) { return; } // short supply buffer.. seems to reduce lag
|
||||||
@ -1170,11 +1265,6 @@ namespace ArdupilotMega.GCSViews
|
|||||||
Array.Reverse(FlightGear, 16, 8);
|
Array.Reverse(FlightGear, 16, 8);
|
||||||
Array.Reverse(FlightGear, 24, 8);
|
Array.Reverse(FlightGear, 24, 8);
|
||||||
|
|
||||||
// old style
|
|
||||||
//string send = "3," + (roll_out * REV_roll).ToString(new System.Globalization.CultureInfo("en-US")) + "," + (pitch_out * REV_pitch * -1).ToString(new System.Globalization.CultureInfo("en-US")) + "," + (rudder_out * REV_rudder).ToString(new System.Globalization.CultureInfo("en-US")) + "," + (throttle_out).ToString(new System.Globalization.CultureInfo("en-US")) + "\r\n";
|
|
||||||
|
|
||||||
//FlightGear = new System.Text.ASCIIEncoding().GetBytes(send);
|
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
XplanesSEND.Send(FlightGear, FlightGear.Length);
|
XplanesSEND.Send(FlightGear, FlightGear.Length);
|
||||||
@ -1267,6 +1357,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
if (RAD_softXplanes.Checked && RAD_softFlightGear.Checked)
|
if (RAD_softXplanes.Checked && RAD_softFlightGear.Checked)
|
||||||
{
|
{
|
||||||
RAD_softFlightGear.Checked = false;
|
RAD_softFlightGear.Checked = false;
|
||||||
|
RAD_aerosimrc.Checked = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1275,6 +1366,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
if (RAD_softFlightGear.Checked && RAD_softXplanes.Checked)
|
if (RAD_softFlightGear.Checked && RAD_softXplanes.Checked)
|
||||||
{
|
{
|
||||||
RAD_softXplanes.Checked = false;
|
RAD_softXplanes.Checked = false;
|
||||||
|
RAD_aerosimrc.Checked = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1381,8 +1473,8 @@ namespace ArdupilotMega.GCSViews
|
|||||||
myPane.XAxis.Scale.Max = 5;
|
myPane.XAxis.Scale.Max = 5;
|
||||||
|
|
||||||
// Make the Y axis scale red
|
// Make the Y axis scale red
|
||||||
myPane.YAxis.Scale.FontSpec.FontColor = Color.Red;
|
//myPane.YAxis.Scale.FontSpec.FontColor = Color.Red;
|
||||||
myPane.YAxis.Title.FontSpec.FontColor = Color.Red;
|
//myPane.YAxis.Title.FontSpec.FontColor = Color.Red;
|
||||||
// turn off the opposite tics so the Y tics don't show up on the Y2 axis
|
// turn off the opposite tics so the Y tics don't show up on the Y2 axis
|
||||||
myPane.YAxis.MajorTic.IsOpposite = false;
|
myPane.YAxis.MajorTic.IsOpposite = false;
|
||||||
myPane.YAxis.MinorTic.IsOpposite = false;
|
myPane.YAxis.MinorTic.IsOpposite = false;
|
||||||
@ -1395,7 +1487,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
//myPane.YAxis.Scale.Max = 1;
|
//myPane.YAxis.Scale.Max = 1;
|
||||||
|
|
||||||
// Fill the axis background with a gradient
|
// Fill the axis background with a gradient
|
||||||
myPane.Chart.Fill = new Fill(Color.White, Color.LightGray, 45.0f);
|
//myPane.Chart.Fill = new Fill(Color.White, Color.LightGray, 45.0f);
|
||||||
|
|
||||||
// Sample at 50ms intervals
|
// Sample at 50ms intervals
|
||||||
timer1.Interval = 50;
|
timer1.Interval = 50;
|
||||||
@ -1605,6 +1697,16 @@ namespace ArdupilotMega.GCSViews
|
|||||||
ofd.InitialDirectory = @"C:\Program Files\FlightGear\bin\Win32\";
|
ofd.InitialDirectory = @"C:\Program Files\FlightGear\bin\Win32\";
|
||||||
extra = " --fg-root=\"C:\\Program Files\\FlightGear\\data\"";
|
extra = " --fg-root=\"C:\\Program Files\\FlightGear\\data\"";
|
||||||
}
|
}
|
||||||
|
else if (File.Exists(@"C:\Program Files\FlightGear 2.4.0\bin\Win32\fgfs.exe"))
|
||||||
|
{
|
||||||
|
ofd.InitialDirectory = @"C:\Program Files\FlightGear 2.4.0\bin\Win32\";
|
||||||
|
extra = " --fg-root=\"C:\\Program Files\\FlightGear 2.4.0\\data\"";
|
||||||
|
}
|
||||||
|
else if (File.Exists(@"C:\Program Files (x86)\FlightGear 2.4.0\bin\Win32\fgfs.exe"))
|
||||||
|
{
|
||||||
|
ofd.InitialDirectory = @"C:\Program Files (x86)\FlightGear 2.4.0\bin\Win32\";
|
||||||
|
extra = " --fg-root=\"C:\\Program Files (x86)\\FlightGear 2.4.0\\data\"";
|
||||||
|
}
|
||||||
else if (File.Exists(@"/usr/games/fgfs"))
|
else if (File.Exists(@"/usr/games/fgfs"))
|
||||||
{
|
{
|
||||||
ofd.InitialDirectory = @"/usr/games";
|
ofd.InitialDirectory = @"/usr/games";
|
||||||
@ -1721,5 +1823,14 @@ namespace ArdupilotMega.GCSViews
|
|||||||
CHKgraphthrottle.Visible = false;
|
CHKgraphthrottle.Visible = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private void RAD_aerosimrc_CheckedChanged(object sender, EventArgs e)
|
||||||
|
{
|
||||||
|
if (RAD_aerosimrc.Checked && RAD_softXplanes.Checked)
|
||||||
|
{
|
||||||
|
RAD_softXplanes.Checked = false;
|
||||||
|
RAD_softFlightGear.Checked = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -144,7 +144,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKREV_roll.ZOrder" xml:space="preserve">
|
<data name=">>CHKREV_roll.ZOrder" xml:space="preserve">
|
||||||
<value>28</value>
|
<value>29</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKREV_pitch.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHKREV_pitch.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -171,7 +171,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKREV_pitch.ZOrder" xml:space="preserve">
|
<data name=">>CHKREV_pitch.ZOrder" xml:space="preserve">
|
||||||
<value>27</value>
|
<value>28</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKREV_rudder.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHKREV_rudder.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -198,7 +198,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKREV_rudder.ZOrder" xml:space="preserve">
|
<data name=">>CHKREV_rudder.ZOrder" xml:space="preserve">
|
||||||
<value>26</value>
|
<value>27</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="GPSrate.Items" xml:space="preserve">
|
<data name="GPSrate.Items" xml:space="preserve">
|
||||||
<value>100</value>
|
<value>100</value>
|
||||||
@ -243,7 +243,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>GPSrate.ZOrder" xml:space="preserve">
|
<data name=">>GPSrate.ZOrder" xml:space="preserve">
|
||||||
<value>25</value>
|
<value>26</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="ConnectComPort.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="ConnectComPort.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>26, 13</value>
|
<value>26, 13</value>
|
||||||
@ -294,7 +294,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>OutputLog.ZOrder" xml:space="preserve">
|
<data name=">>OutputLog.ZOrder" xml:space="preserve">
|
||||||
<value>24</value>
|
<value>25</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="TXT_roll.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="TXT_roll.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>67, 22</value>
|
<value>67, 22</value>
|
||||||
@ -489,7 +489,7 @@
|
|||||||
<value>6</value>
|
<value>6</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="SaveSettings.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="SaveSettings.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>566, 280</value>
|
<value>566, 330</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="SaveSettings.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="SaveSettings.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>64, 34</value>
|
<value>64, 34</value>
|
||||||
@ -510,7 +510,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>SaveSettings.ZOrder" xml:space="preserve">
|
<data name=">>SaveSettings.ZOrder" xml:space="preserve">
|
||||||
<value>23</value>
|
<value>24</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="RAD_softXplanes.AutoSize" type="System.Boolean, mscorlib">
|
<data name="RAD_softXplanes.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -527,6 +527,12 @@
|
|||||||
<data name="RAD_softXplanes.Text" xml:space="preserve">
|
<data name="RAD_softXplanes.Text" xml:space="preserve">
|
||||||
<value>X-plane</value>
|
<value>X-plane</value>
|
||||||
</data>
|
</data>
|
||||||
|
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||||
|
<value>301, 17</value>
|
||||||
|
</metadata>
|
||||||
|
<data name="RAD_softXplanes.ToolTip" xml:space="preserve">
|
||||||
|
<value>Can Do Plane/Quad with plugin</value>
|
||||||
|
</data>
|
||||||
<data name=">>RAD_softXplanes.Name" xml:space="preserve">
|
<data name=">>RAD_softXplanes.Name" xml:space="preserve">
|
||||||
<value>RAD_softXplanes</value>
|
<value>RAD_softXplanes</value>
|
||||||
</data>
|
</data>
|
||||||
@ -537,7 +543,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>RAD_softXplanes.ZOrder" xml:space="preserve">
|
<data name=">>RAD_softXplanes.ZOrder" xml:space="preserve">
|
||||||
<value>22</value>
|
<value>23</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="RAD_softFlightGear.AutoSize" type="System.Boolean, mscorlib">
|
<data name="RAD_softFlightGear.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -554,6 +560,9 @@
|
|||||||
<data name="RAD_softFlightGear.Text" xml:space="preserve">
|
<data name="RAD_softFlightGear.Text" xml:space="preserve">
|
||||||
<value>FlightGear</value>
|
<value>FlightGear</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="RAD_softFlightGear.ToolTip" xml:space="preserve">
|
||||||
|
<value>Can do Plane and Quad with model</value>
|
||||||
|
</data>
|
||||||
<data name=">>RAD_softFlightGear.Name" xml:space="preserve">
|
<data name=">>RAD_softFlightGear.Name" xml:space="preserve">
|
||||||
<value>RAD_softFlightGear</value>
|
<value>RAD_softFlightGear</value>
|
||||||
</data>
|
</data>
|
||||||
@ -564,7 +573,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>RAD_softFlightGear.ZOrder" xml:space="preserve">
|
<data name=">>RAD_softFlightGear.ZOrder" xml:space="preserve">
|
||||||
<value>21</value>
|
<value>22</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="TXT_servoroll.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="TXT_servoroll.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>67, 24</value>
|
<value>67, 24</value>
|
||||||
@ -765,7 +774,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel1.ZOrder" xml:space="preserve">
|
<data name=">>panel1.ZOrder" xml:space="preserve">
|
||||||
<value>20</value>
|
<value>21</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label30.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="label30.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>7, 100</value>
|
<value>7, 100</value>
|
||||||
@ -927,7 +936,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel2.ZOrder" xml:space="preserve">
|
<data name=">>panel2.ZOrder" xml:space="preserve">
|
||||||
<value>19</value>
|
<value>20</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label8.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="label8.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>7, 27</value>
|
<value>7, 27</value>
|
||||||
@ -1140,7 +1149,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel3.ZOrder" xml:space="preserve">
|
<data name=">>panel3.ZOrder" xml:space="preserve">
|
||||||
<value>18</value>
|
<value>19</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label20.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="label20.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>72, 104</value>
|
<value>72, 104</value>
|
||||||
@ -1275,7 +1284,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel4.ZOrder" xml:space="preserve">
|
<data name=">>panel4.ZOrder" xml:space="preserve">
|
||||||
<value>17</value>
|
<value>18</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label17.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="label17.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>535, 9</value>
|
<value>535, 9</value>
|
||||||
@ -1299,7 +1308,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>label17.ZOrder" xml:space="preserve">
|
<data name=">>label17.ZOrder" xml:space="preserve">
|
||||||
<value>16</value>
|
<value>17</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="panel5.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="panel5.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>13, 5</value>
|
<value>13, 5</value>
|
||||||
@ -1320,7 +1329,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel5.ZOrder" xml:space="preserve">
|
<data name=">>panel5.ZOrder" xml:space="preserve">
|
||||||
<value>15</value>
|
<value>16</value>
|
||||||
</data>
|
</data>
|
||||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||||
<data name="zg1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="zg1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
@ -1345,7 +1354,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>zg1.ZOrder" xml:space="preserve">
|
<data name=">>zg1.ZOrder" xml:space="preserve">
|
||||||
<value>14</value>
|
<value>15</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="timer1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
<metadata name="timer1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||||
<value>17, 17</value>
|
<value>17, 17</value>
|
||||||
@ -1657,7 +1666,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel6.ZOrder" xml:space="preserve">
|
<data name=">>panel6.ZOrder" xml:space="preserve">
|
||||||
<value>13</value>
|
<value>14</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label26.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="label26.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>508, 330</value>
|
<value>508, 330</value>
|
||||||
@ -1681,13 +1690,13 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>label26.ZOrder" xml:space="preserve">
|
<data name=">>label26.ZOrder" xml:space="preserve">
|
||||||
<value>12</value>
|
<value>13</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKdisplayall.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHKdisplayall.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKdisplayall.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="CHKdisplayall.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>345, 41</value>
|
<value>456, 41</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKdisplayall.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="CHKdisplayall.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>74, 17</value>
|
<value>74, 17</value>
|
||||||
@ -1708,7 +1717,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKdisplayall.ZOrder" xml:space="preserve">
|
<data name=">>CHKdisplayall.ZOrder" xml:space="preserve">
|
||||||
<value>11</value>
|
<value>12</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKgraphroll.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="CHKgraphroll.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Left</value>
|
<value>Bottom, Left</value>
|
||||||
@ -1738,7 +1747,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKgraphroll.ZOrder" xml:space="preserve">
|
<data name=">>CHKgraphroll.ZOrder" xml:space="preserve">
|
||||||
<value>10</value>
|
<value>11</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKgraphpitch.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="CHKgraphpitch.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Left</value>
|
<value>Bottom, Left</value>
|
||||||
@ -1768,7 +1777,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKgraphpitch.ZOrder" xml:space="preserve">
|
<data name=">>CHKgraphpitch.ZOrder" xml:space="preserve">
|
||||||
<value>9</value>
|
<value>10</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKgraphrudder.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="CHKgraphrudder.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Left</value>
|
<value>Bottom, Left</value>
|
||||||
@ -1798,7 +1807,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKgraphrudder.ZOrder" xml:space="preserve">
|
<data name=">>CHKgraphrudder.ZOrder" xml:space="preserve">
|
||||||
<value>8</value>
|
<value>9</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKgraphthrottle.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="CHKgraphthrottle.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Left</value>
|
<value>Bottom, Left</value>
|
||||||
@ -1828,7 +1837,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKgraphthrottle.ZOrder" xml:space="preserve">
|
<data name=">>CHKgraphthrottle.ZOrder" xml:space="preserve">
|
||||||
<value>7</value>
|
<value>8</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="but_advsettings.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="but_advsettings.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>566, 368</value>
|
<value>566, 368</value>
|
||||||
@ -1852,13 +1861,13 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>but_advsettings.ZOrder" xml:space="preserve">
|
<data name=">>but_advsettings.ZOrder" xml:space="preserve">
|
||||||
<value>6</value>
|
<value>7</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="chkSensor.AutoSize" type="System.Boolean, mscorlib">
|
<data name="chkSensor.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="chkSensor.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="chkSensor.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>566, 317</value>
|
<value>566, 186</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="chkSensor.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="chkSensor.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>59, 17</value>
|
<value>59, 17</value>
|
||||||
@ -1879,7 +1888,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>chkSensor.ZOrder" xml:space="preserve">
|
<data name=">>chkSensor.ZOrder" xml:space="preserve">
|
||||||
<value>5</value>
|
<value>6</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_quad.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHK_quad.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -1888,7 +1897,7 @@
|
|||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_quad.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="CHK_quad.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>566, 334</value>
|
<value>566, 203</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_quad.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="CHK_quad.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>52, 17</value>
|
<value>52, 17</value>
|
||||||
@ -1909,7 +1918,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHK_quad.ZOrder" xml:space="preserve">
|
<data name=">>CHK_quad.ZOrder" xml:space="preserve">
|
||||||
<value>4</value>
|
<value>5</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_startfgquad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_startfgquad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1936,7 +1945,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_startfgquad.ZOrder" xml:space="preserve">
|
<data name=">>BUT_startfgquad.ZOrder" xml:space="preserve">
|
||||||
<value>3</value>
|
<value>4</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_startfgplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_startfgplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1963,7 +1972,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_startfgplane.ZOrder" xml:space="preserve">
|
<data name=">>BUT_startfgplane.ZOrder" xml:space="preserve">
|
||||||
<value>2</value>
|
<value>3</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_startxplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_startxplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1990,7 +1999,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_startxplane.ZOrder" xml:space="preserve">
|
<data name=">>BUT_startxplane.ZOrder" xml:space="preserve">
|
||||||
<value>1</value>
|
<value>2</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_heli.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHK_heli.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -1999,7 +2008,7 @@
|
|||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_heli.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="CHK_heli.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>566, 350</value>
|
<value>566, 219</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_heli.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="CHK_heli.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>44, 17</value>
|
<value>44, 17</value>
|
||||||
@ -2020,6 +2029,39 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHK_heli.ZOrder" xml:space="preserve">
|
<data name=">>CHK_heli.ZOrder" xml:space="preserve">
|
||||||
|
<value>1</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.AutoSize" type="System.Boolean, mscorlib">
|
||||||
|
<value>True</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
|
<value>NoControl</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>345, 40</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>79, 17</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>48</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.Text" xml:space="preserve">
|
||||||
|
<value>AeroSimRC</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.ToolTip" xml:space="preserve">
|
||||||
|
<value>Can do Plane/Heli/Quads</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>RAD_aerosimrc.Name" xml:space="preserve">
|
||||||
|
<value>RAD_aerosimrc</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>RAD_aerosimrc.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>RAD_aerosimrc.Parent" xml:space="preserve">
|
||||||
|
<value>$this</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>RAD_aerosimrc.ZOrder" xml:space="preserve">
|
||||||
<value>0</value>
|
<value>0</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||||
@ -2043,6 +2085,12 @@
|
|||||||
<data name=">>timer1.Type" xml:space="preserve">
|
<data name=">>timer1.Type" xml:space="preserve">
|
||||||
<value>System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
<value>System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name=">>toolTip1.Name" xml:space="preserve">
|
||||||
|
<value>toolTip1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>toolTip1.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
<data name=">>$this.Name" xml:space="preserve">
|
<data name=">>$this.Name" xml:space="preserve">
|
||||||
<value>Simulation</value>
|
<value>Simulation</value>
|
||||||
</data>
|
</data>
|
||||||
|
@ -197,6 +197,8 @@ namespace ArdupilotMega
|
|||||||
sw.Close();
|
sw.Close();
|
||||||
TextReader tr = new StreamReader(logfile);
|
TextReader tr = new StreamReader(logfile);
|
||||||
|
|
||||||
|
MainV2.cs.firmware = MainV2.Firmwares.ArduPlane;
|
||||||
|
|
||||||
while (tr.Peek() != -1)
|
while (tr.Peek() != -1)
|
||||||
{
|
{
|
||||||
processLine(tr.ReadLine());
|
processLine(tr.ReadLine());
|
||||||
@ -322,7 +324,7 @@ namespace ArdupilotMega
|
|||||||
lastpos = (position[positionindex][position[positionindex].Count - 1]);
|
lastpos = (position[positionindex][position[positionindex].Count - 1]);
|
||||||
lastline = line;
|
lastline = line;
|
||||||
}
|
}
|
||||||
if (items[0].Contains("GPS") && items[4] != "0" && items[4] != "-1")
|
if (items[0].Contains("GPS") && items[4] != "0" && items[4] != "-1" && items.Length <= 9)
|
||||||
{
|
{
|
||||||
if (position[positionindex] == null)
|
if (position[positionindex] == null)
|
||||||
position[positionindex] = new List<Point3D>();
|
position[positionindex] = new List<Point3D>();
|
||||||
@ -710,6 +712,8 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
TextReader tr = new StreamReader(logfile);
|
TextReader tr = new StreamReader(logfile);
|
||||||
|
|
||||||
|
MainV2.cs.firmware = MainV2.Firmwares.ArduPlane;
|
||||||
|
|
||||||
while (tr.Peek() != -1)
|
while (tr.Peek() != -1)
|
||||||
{
|
{
|
||||||
processLine(tr.ReadLine());
|
processLine(tr.ReadLine());
|
||||||
@ -783,6 +787,8 @@ namespace ArdupilotMega
|
|||||||
{
|
{
|
||||||
TextReader tr = new StreamReader(logfile);
|
TextReader tr = new StreamReader(logfile);
|
||||||
|
|
||||||
|
MainV2.cs.firmware = MainV2.Firmwares.ArduPlane;
|
||||||
|
|
||||||
while (tr.Peek() != -1)
|
while (tr.Peek() != -1)
|
||||||
{
|
{
|
||||||
processLine(tr.ReadLine());
|
processLine(tr.ReadLine());
|
||||||
|
@ -80,7 +80,7 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
georefimage temp = new georefimage();
|
georefimage temp = new georefimage();
|
||||||
|
|
||||||
//temp.dowork(141);
|
//temp.dowork(244 + 60*60*24 * -1 );
|
||||||
|
|
||||||
//return;
|
//return;
|
||||||
|
|
||||||
|
@ -34,5 +34,5 @@ using System.Resources;
|
|||||||
// by using the '*' as shown below:
|
// by using the '*' as shown below:
|
||||||
// [assembly: AssemblyVersion("1.0.*")]
|
// [assembly: AssemblyVersion("1.0.*")]
|
||||||
[assembly: AssemblyVersion("1.0.0.0")]
|
[assembly: AssemblyVersion("1.0.0.0")]
|
||||||
[assembly: AssemblyFileVersion("1.0.79")]
|
[assembly: AssemblyFileVersion("1.0.80")]
|
||||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||||
|
1210
Tools/ArdupilotMegaPlanner/Properties/Resources.zh-Hans.resx
Normal file
1210
Tools/ArdupilotMegaPlanner/Properties/Resources.zh-Hans.resx
Normal file
File diff suppressed because it is too large
Load Diff
BIN
Tools/ArdupilotMegaPlanner/Resources/frames_color.rar
Normal file
BIN
Tools/ArdupilotMegaPlanner/Resources/frames_color.rar
Normal file
Binary file not shown.
@ -1,3 +1,4 @@
|
|||||||
|
|
||||||
*.pdb
|
*.pdb
|
||||||
*.xml
|
*.xml
|
||||||
|
*.etag
|
@ -0,0 +1,18 @@
|
|||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<asmv1:assembly xsi:schemaLocation="urn:schemas-microsoft-com:asm.v1 assembly.adaptive.xsd" manifestVersion="1.0" xmlns:asmv3="urn:schemas-microsoft-com:asm.v3" xmlns:dsig="http://www.w3.org/2000/09/xmldsig#" xmlns:co.v1="urn:schemas-microsoft-com:clickonce.v1" xmlns:co.v2="urn:schemas-microsoft-com:clickonce.v2" xmlns="urn:schemas-microsoft-com:asm.v2" xmlns:asmv1="urn:schemas-microsoft-com:asm.v1" xmlns:asmv2="urn:schemas-microsoft-com:asm.v2" xmlns:xrml="urn:mpeg:mpeg21:2003:01-REL-R-NS" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance">
|
||||||
|
<assemblyIdentity name="ArdupilotMegaPlanner.application" version="0.0.0.1" publicKeyToken="0000000000000000" language="en-US" processorArchitecture="x86" xmlns="urn:schemas-microsoft-com:asm.v1" />
|
||||||
|
<description asmv2:publisher="Michael Oborne" asmv2:product="ArdupilotMegaPlanner" xmlns="urn:schemas-microsoft-com:asm.v1" />
|
||||||
|
<deployment install="true" />
|
||||||
|
<dependency>
|
||||||
|
<dependentAssembly dependencyType="install" codebase="ArdupilotMegaPlanner.exe.manifest" size="18145">
|
||||||
|
<assemblyIdentity name="ArdupilotMegaPlanner.exe" version="0.0.0.1" publicKeyToken="0000000000000000" language="en-US" processorArchitecture="x86" type="win32" />
|
||||||
|
<hash>
|
||||||
|
<dsig:Transforms>
|
||||||
|
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
|
||||||
|
</dsig:Transforms>
|
||||||
|
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
|
||||||
|
<dsig:DigestValue>KL2GgPg3v0nfw+58LySJfeIHyEM=</dsig:DigestValue>
|
||||||
|
</hash>
|
||||||
|
</dependentAssembly>
|
||||||
|
</dependency>
|
||||||
|
</asmv1:assembly>
|
File diff suppressed because it is too large
Load Diff
@ -144,7 +144,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKREV_roll.ZOrder" xml:space="preserve">
|
<data name=">>CHKREV_roll.ZOrder" xml:space="preserve">
|
||||||
<value>28</value>
|
<value>29</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKREV_pitch.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHKREV_pitch.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -171,7 +171,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKREV_pitch.ZOrder" xml:space="preserve">
|
<data name=">>CHKREV_pitch.ZOrder" xml:space="preserve">
|
||||||
<value>27</value>
|
<value>28</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKREV_rudder.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHKREV_rudder.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -198,7 +198,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKREV_rudder.ZOrder" xml:space="preserve">
|
<data name=">>CHKREV_rudder.ZOrder" xml:space="preserve">
|
||||||
<value>26</value>
|
<value>27</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="GPSrate.Items" xml:space="preserve">
|
<data name="GPSrate.Items" xml:space="preserve">
|
||||||
<value>100</value>
|
<value>100</value>
|
||||||
@ -243,7 +243,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>GPSrate.ZOrder" xml:space="preserve">
|
<data name=">>GPSrate.ZOrder" xml:space="preserve">
|
||||||
<value>25</value>
|
<value>26</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="ConnectComPort.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="ConnectComPort.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>26, 13</value>
|
<value>26, 13</value>
|
||||||
@ -294,7 +294,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>OutputLog.ZOrder" xml:space="preserve">
|
<data name=">>OutputLog.ZOrder" xml:space="preserve">
|
||||||
<value>24</value>
|
<value>25</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="TXT_roll.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="TXT_roll.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>67, 22</value>
|
<value>67, 22</value>
|
||||||
@ -489,7 +489,7 @@
|
|||||||
<value>6</value>
|
<value>6</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="SaveSettings.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="SaveSettings.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>566, 280</value>
|
<value>566, 330</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="SaveSettings.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="SaveSettings.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>64, 34</value>
|
<value>64, 34</value>
|
||||||
@ -510,7 +510,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>SaveSettings.ZOrder" xml:space="preserve">
|
<data name=">>SaveSettings.ZOrder" xml:space="preserve">
|
||||||
<value>23</value>
|
<value>24</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="RAD_softXplanes.AutoSize" type="System.Boolean, mscorlib">
|
<data name="RAD_softXplanes.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -527,6 +527,12 @@
|
|||||||
<data name="RAD_softXplanes.Text" xml:space="preserve">
|
<data name="RAD_softXplanes.Text" xml:space="preserve">
|
||||||
<value>X-plane</value>
|
<value>X-plane</value>
|
||||||
</data>
|
</data>
|
||||||
|
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||||
|
<value>301, 17</value>
|
||||||
|
</metadata>
|
||||||
|
<data name="RAD_softXplanes.ToolTip" xml:space="preserve">
|
||||||
|
<value>Can Do Plane/Quad with plugin</value>
|
||||||
|
</data>
|
||||||
<data name=">>RAD_softXplanes.Name" xml:space="preserve">
|
<data name=">>RAD_softXplanes.Name" xml:space="preserve">
|
||||||
<value>RAD_softXplanes</value>
|
<value>RAD_softXplanes</value>
|
||||||
</data>
|
</data>
|
||||||
@ -537,7 +543,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>RAD_softXplanes.ZOrder" xml:space="preserve">
|
<data name=">>RAD_softXplanes.ZOrder" xml:space="preserve">
|
||||||
<value>22</value>
|
<value>23</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="RAD_softFlightGear.AutoSize" type="System.Boolean, mscorlib">
|
<data name="RAD_softFlightGear.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -554,6 +560,9 @@
|
|||||||
<data name="RAD_softFlightGear.Text" xml:space="preserve">
|
<data name="RAD_softFlightGear.Text" xml:space="preserve">
|
||||||
<value>FlightGear</value>
|
<value>FlightGear</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="RAD_softFlightGear.ToolTip" xml:space="preserve">
|
||||||
|
<value>Can do Plane and Quad with model</value>
|
||||||
|
</data>
|
||||||
<data name=">>RAD_softFlightGear.Name" xml:space="preserve">
|
<data name=">>RAD_softFlightGear.Name" xml:space="preserve">
|
||||||
<value>RAD_softFlightGear</value>
|
<value>RAD_softFlightGear</value>
|
||||||
</data>
|
</data>
|
||||||
@ -564,7 +573,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>RAD_softFlightGear.ZOrder" xml:space="preserve">
|
<data name=">>RAD_softFlightGear.ZOrder" xml:space="preserve">
|
||||||
<value>21</value>
|
<value>22</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="TXT_servoroll.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="TXT_servoroll.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>67, 24</value>
|
<value>67, 24</value>
|
||||||
@ -765,7 +774,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel1.ZOrder" xml:space="preserve">
|
<data name=">>panel1.ZOrder" xml:space="preserve">
|
||||||
<value>20</value>
|
<value>21</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label30.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="label30.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>7, 100</value>
|
<value>7, 100</value>
|
||||||
@ -927,7 +936,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel2.ZOrder" xml:space="preserve">
|
<data name=">>panel2.ZOrder" xml:space="preserve">
|
||||||
<value>19</value>
|
<value>20</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label8.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="label8.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>7, 27</value>
|
<value>7, 27</value>
|
||||||
@ -1140,7 +1149,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel3.ZOrder" xml:space="preserve">
|
<data name=">>panel3.ZOrder" xml:space="preserve">
|
||||||
<value>18</value>
|
<value>19</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label20.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="label20.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>72, 104</value>
|
<value>72, 104</value>
|
||||||
@ -1275,7 +1284,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel4.ZOrder" xml:space="preserve">
|
<data name=">>panel4.ZOrder" xml:space="preserve">
|
||||||
<value>17</value>
|
<value>18</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label17.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="label17.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>535, 9</value>
|
<value>535, 9</value>
|
||||||
@ -1299,7 +1308,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>label17.ZOrder" xml:space="preserve">
|
<data name=">>label17.ZOrder" xml:space="preserve">
|
||||||
<value>16</value>
|
<value>17</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="panel5.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="panel5.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>13, 5</value>
|
<value>13, 5</value>
|
||||||
@ -1320,7 +1329,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel5.ZOrder" xml:space="preserve">
|
<data name=">>panel5.ZOrder" xml:space="preserve">
|
||||||
<value>15</value>
|
<value>16</value>
|
||||||
</data>
|
</data>
|
||||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||||
<data name="zg1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="zg1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
@ -1345,7 +1354,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>zg1.ZOrder" xml:space="preserve">
|
<data name=">>zg1.ZOrder" xml:space="preserve">
|
||||||
<value>14</value>
|
<value>15</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="timer1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
<metadata name="timer1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||||
<value>17, 17</value>
|
<value>17, 17</value>
|
||||||
@ -1657,7 +1666,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>panel6.ZOrder" xml:space="preserve">
|
<data name=">>panel6.ZOrder" xml:space="preserve">
|
||||||
<value>13</value>
|
<value>14</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label26.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="label26.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>508, 330</value>
|
<value>508, 330</value>
|
||||||
@ -1681,13 +1690,13 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>label26.ZOrder" xml:space="preserve">
|
<data name=">>label26.ZOrder" xml:space="preserve">
|
||||||
<value>12</value>
|
<value>13</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKdisplayall.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHKdisplayall.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKdisplayall.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="CHKdisplayall.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>345, 41</value>
|
<value>456, 41</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKdisplayall.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="CHKdisplayall.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>74, 17</value>
|
<value>74, 17</value>
|
||||||
@ -1708,7 +1717,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKdisplayall.ZOrder" xml:space="preserve">
|
<data name=">>CHKdisplayall.ZOrder" xml:space="preserve">
|
||||||
<value>11</value>
|
<value>12</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKgraphroll.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="CHKgraphroll.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Left</value>
|
<value>Bottom, Left</value>
|
||||||
@ -1738,7 +1747,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKgraphroll.ZOrder" xml:space="preserve">
|
<data name=">>CHKgraphroll.ZOrder" xml:space="preserve">
|
||||||
<value>10</value>
|
<value>11</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKgraphpitch.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="CHKgraphpitch.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Left</value>
|
<value>Bottom, Left</value>
|
||||||
@ -1768,7 +1777,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKgraphpitch.ZOrder" xml:space="preserve">
|
<data name=">>CHKgraphpitch.ZOrder" xml:space="preserve">
|
||||||
<value>9</value>
|
<value>10</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKgraphrudder.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="CHKgraphrudder.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Left</value>
|
<value>Bottom, Left</value>
|
||||||
@ -1798,7 +1807,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKgraphrudder.ZOrder" xml:space="preserve">
|
<data name=">>CHKgraphrudder.ZOrder" xml:space="preserve">
|
||||||
<value>8</value>
|
<value>9</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHKgraphthrottle.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="CHKgraphthrottle.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Left</value>
|
<value>Bottom, Left</value>
|
||||||
@ -1828,7 +1837,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHKgraphthrottle.ZOrder" xml:space="preserve">
|
<data name=">>CHKgraphthrottle.ZOrder" xml:space="preserve">
|
||||||
<value>7</value>
|
<value>8</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="but_advsettings.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="but_advsettings.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>566, 368</value>
|
<value>566, 368</value>
|
||||||
@ -1852,13 +1861,13 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>but_advsettings.ZOrder" xml:space="preserve">
|
<data name=">>but_advsettings.ZOrder" xml:space="preserve">
|
||||||
<value>6</value>
|
<value>7</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="chkSensor.AutoSize" type="System.Boolean, mscorlib">
|
<data name="chkSensor.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="chkSensor.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="chkSensor.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>566, 317</value>
|
<value>566, 186</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="chkSensor.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="chkSensor.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>59, 17</value>
|
<value>59, 17</value>
|
||||||
@ -1879,7 +1888,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>chkSensor.ZOrder" xml:space="preserve">
|
<data name=">>chkSensor.ZOrder" xml:space="preserve">
|
||||||
<value>5</value>
|
<value>6</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_quad.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHK_quad.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -1888,7 +1897,7 @@
|
|||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_quad.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="CHK_quad.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>566, 334</value>
|
<value>566, 203</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_quad.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="CHK_quad.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>52, 17</value>
|
<value>52, 17</value>
|
||||||
@ -1909,7 +1918,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHK_quad.ZOrder" xml:space="preserve">
|
<data name=">>CHK_quad.ZOrder" xml:space="preserve">
|
||||||
<value>4</value>
|
<value>5</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_startfgquad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_startfgquad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1936,7 +1945,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_startfgquad.ZOrder" xml:space="preserve">
|
<data name=">>BUT_startfgquad.ZOrder" xml:space="preserve">
|
||||||
<value>3</value>
|
<value>4</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_startfgplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_startfgplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1963,7 +1972,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_startfgplane.ZOrder" xml:space="preserve">
|
<data name=">>BUT_startfgplane.ZOrder" xml:space="preserve">
|
||||||
<value>2</value>
|
<value>3</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_startxplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_startxplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1990,7 +1999,7 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_startxplane.ZOrder" xml:space="preserve">
|
<data name=">>BUT_startxplane.ZOrder" xml:space="preserve">
|
||||||
<value>1</value>
|
<value>2</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_heli.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHK_heli.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -1999,7 +2008,7 @@
|
|||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_heli.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="CHK_heli.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>566, 350</value>
|
<value>566, 219</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_heli.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="CHK_heli.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>44, 17</value>
|
<value>44, 17</value>
|
||||||
@ -2020,6 +2029,39 @@
|
|||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHK_heli.ZOrder" xml:space="preserve">
|
<data name=">>CHK_heli.ZOrder" xml:space="preserve">
|
||||||
|
<value>1</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.AutoSize" type="System.Boolean, mscorlib">
|
||||||
|
<value>True</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
|
<value>NoControl</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>345, 40</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>79, 17</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>48</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.Text" xml:space="preserve">
|
||||||
|
<value>AeroSimRC</value>
|
||||||
|
</data>
|
||||||
|
<data name="RAD_aerosimrc.ToolTip" xml:space="preserve">
|
||||||
|
<value>Can do Plane/Heli/Quads</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>RAD_aerosimrc.Name" xml:space="preserve">
|
||||||
|
<value>RAD_aerosimrc</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>RAD_aerosimrc.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>RAD_aerosimrc.Parent" xml:space="preserve">
|
||||||
|
<value>$this</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>RAD_aerosimrc.ZOrder" xml:space="preserve">
|
||||||
<value>0</value>
|
<value>0</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||||
@ -2043,6 +2085,12 @@
|
|||||||
<data name=">>timer1.Type" xml:space="preserve">
|
<data name=">>timer1.Type" xml:space="preserve">
|
||||||
<value>System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
<value>System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name=">>toolTip1.Name" xml:space="preserve">
|
||||||
|
<value>toolTip1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>toolTip1.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
<data name=">>$this.Name" xml:space="preserve">
|
<data name=">>$this.Name" xml:space="preserve">
|
||||||
<value>Simulation</value>
|
<value>Simulation</value>
|
||||||
</data>
|
</data>
|
||||||
|
@ -71,13 +71,16 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
public void dowork(float offsetseconds)
|
public void dowork(float offsetseconds)
|
||||||
{
|
{
|
||||||
|
DateTime localmin = DateTime.MaxValue;
|
||||||
|
DateTime localmax = DateTime.MinValue;
|
||||||
|
|
||||||
DateTime startTime = DateTime.MinValue;
|
DateTime startTime = DateTime.MinValue;
|
||||||
|
|
||||||
logFile = @"C:\Users\hog\Pictures\sams mums 22-6-2011\23-06-11 10-03 4.log";
|
logFile = @"C:\temp\farm 1-10-2011\100SSCAM\2011-10-01 11-48 1.log";
|
||||||
|
|
||||||
List<string[]> list = readLog(logFile);
|
List<string[]> list = readLog(logFile);
|
||||||
|
|
||||||
dirWithImages = @"C:\Users\hog\Pictures\sams mums 22-6-2011";
|
dirWithImages = @"C:\temp\farm 1-10-2011\100SSCAM";
|
||||||
|
|
||||||
string[] files = Directory.GetFiles(dirWithImages);
|
string[] files = Directory.GetFiles(dirWithImages);
|
||||||
|
|
||||||
@ -95,21 +98,37 @@ namespace ArdupilotMega
|
|||||||
DateTime dt = getPhotoTime(file);
|
DateTime dt = getPhotoTime(file);
|
||||||
|
|
||||||
if (startTime == DateTime.MinValue)
|
if (startTime == DateTime.MinValue)
|
||||||
startTime = new DateTime(dt.Year,dt.Month,dt.Day,0,0,0,0,DateTimeKind.Utc).ToLocalTime();
|
{
|
||||||
|
startTime = new DateTime(dt.Year, dt.Month, dt.Day, 0, 0, 0, 0, DateTimeKind.Utc).ToLocalTime();
|
||||||
|
|
||||||
|
foreach (string[] arr in list)
|
||||||
|
{
|
||||||
|
DateTime crap = startTime.AddMilliseconds(int.Parse(arr[1])).AddSeconds(offsetseconds);
|
||||||
|
|
||||||
|
if (localmin > crap)
|
||||||
|
localmin = crap;
|
||||||
|
if (localmax < crap)
|
||||||
|
localmax = crap;
|
||||||
|
}
|
||||||
|
|
||||||
|
Console.WriteLine("min " + localmin + " max " + localmax);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
foreach (string[] arr in list)
|
foreach (string[] arr in list)
|
||||||
{
|
{
|
||||||
DateTime crap = startTime.AddMilliseconds(int.Parse(arr[1])).AddSeconds(offsetseconds);
|
DateTime crap = startTime.AddMilliseconds(int.Parse(arr[1])).AddSeconds(offsetseconds);
|
||||||
|
|
||||||
//Console.Write(dt + " " + crap + "\r");
|
Console.Write("ph " + dt + " log " + crap + " \r");
|
||||||
|
|
||||||
if (dt.Equals(crap))
|
if (dt.Equals(crap))
|
||||||
{
|
{
|
||||||
sw2.WriteLine(Path.GetFileNameWithoutExtension(file) + " " + arr[5] + " " + arr[4] + " " + arr[6]);
|
sw2.WriteLine(Path.GetFileNameWithoutExtension(file) + " " + arr[5] + " " + arr[4] + " " + arr[7]);
|
||||||
sw.WriteLine(Path.GetFileNameWithoutExtension(file) + "\t" + crap.ToString("yyyy:MM:dd HH:mm:ss") +"\t"+ arr[5] + "\t" + arr[4] + "\t" + arr[6]);
|
sw.WriteLine(Path.GetFileNameWithoutExtension(file) + "\t" + crap.ToString("yyyy:MM:dd HH:mm:ss") +"\t"+ arr[5] + "\t" + arr[4] + "\t" + arr[7]);
|
||||||
sw.Flush();
|
sw.Flush();
|
||||||
sw2.Flush();
|
sw2.Flush();
|
||||||
Console.WriteLine(Path.GetFileNameWithoutExtension(file) + " " + arr[5] + " " + arr[4] + " " + arr[6] + " ");
|
Console.WriteLine(Path.GetFileNameWithoutExtension(file) + " " + arr[5] + " " + arr[4] + " " + arr[7] + " ");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
//Console.WriteLine(crap);
|
//Console.WriteLine(crap);
|
||||||
|
Loading…
Reference in New Issue
Block a user