mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Merge branch 'master' of https://code.google.com/p/ardupilot-mega into auto-approach
This commit is contained in:
commit
692bbee233
@ -199,7 +199,11 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
|
||||
#endif
|
||||
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
AP_OpticalFlow_ADNS3080 optflow(OPTFLOW_CS_PIN);
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
AP_OpticalFlow_ADNS3080_APM2 optflow(OPTFLOW_CS_PIN);
|
||||
#else
|
||||
AP_OpticalFlow_ADNS3080 optflow(OPTFLOW_CS_PIN);
|
||||
#endif
|
||||
#else
|
||||
AP_OpticalFlow optflow;
|
||||
#endif
|
||||
@ -484,6 +488,12 @@ static const float radius_of_earth = 6378100; // meters
|
||||
// Used by Mavlink for unknow reasons
|
||||
static const float gravity = 9.81; // meters/ sec^2
|
||||
|
||||
// Unions for getting byte values
|
||||
union float_int{
|
||||
int32_t int_value;
|
||||
float float_value;
|
||||
} float_int;
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Location & Navigation
|
||||
@ -2060,10 +2070,6 @@ static void tuning(){
|
||||
|
||||
switch(g.radio_tuning){
|
||||
|
||||
case CH6_DAMP:
|
||||
g.stabilize_d.set(tuning_value);
|
||||
break;
|
||||
|
||||
case CH6_RATE_KD:
|
||||
g.pid_rate_roll.kD(tuning_value);
|
||||
g.pid_rate_pitch.kD(tuning_value);
|
||||
@ -2079,6 +2085,7 @@ static void tuning(){
|
||||
g.pi_stabilize_pitch.kI(tuning_value);
|
||||
break;
|
||||
|
||||
case CH6_DAMP:
|
||||
case CH6_STABILIZE_KD:
|
||||
g.stabilize_d = tuning_value;
|
||||
break;
|
||||
|
@ -586,9 +586,11 @@ static int32_t
|
||||
get_of_roll(int32_t control_roll)
|
||||
{
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
static int8_t log_counter = 0; // used to slow down logging of PID values to dataflash
|
||||
static float tot_x_cm = 0; // total distance from target
|
||||
static uint32_t last_of_roll_update = 0;
|
||||
int32_t new_roll = 0;
|
||||
int32_t p,i,d;
|
||||
|
||||
// check if new optflow data available
|
||||
if( optflow.last_update != last_of_roll_update) {
|
||||
@ -599,17 +601,35 @@ get_of_roll(int32_t control_roll)
|
||||
|
||||
// only stop roll if caller isn't modifying roll
|
||||
if( control_roll == 0 && current_loc.alt < 1500) {
|
||||
new_roll = g.pid_optflow_roll.get_pid(-tot_x_cm, 1.0); // we could use the last update time to calculate the time change
|
||||
p = g.pid_optflow_roll.get_p(-tot_x_cm);
|
||||
i = g.pid_optflow_roll.get_i(-tot_x_cm,1.0); // we could use the last update time to calculate the time change
|
||||
d = g.pid_optflow_roll.get_d(-tot_x_cm,1.0);
|
||||
new_roll = p+i+d;
|
||||
}else{
|
||||
g.pid_optflow_roll.reset_I();
|
||||
tot_x_cm = 0;
|
||||
p = 0; // for logging
|
||||
i = 0;
|
||||
d = 0;
|
||||
}
|
||||
// limit amount of change and maximum angle
|
||||
of_roll = constrain(new_roll, (of_roll-20), (of_roll+20));
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
// log output if PID logging is on and we are tuning the rate P, I or D gains
|
||||
if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_OPTFLOW_KP || g.radio_tuning == CH6_OPTFLOW_KI || g.radio_tuning == CH6_OPTFLOW_KD) ) {
|
||||
log_counter++;
|
||||
if( log_counter >= 5 ) { // (update rate / desired output rate) = (100hz / 10hz) = 10
|
||||
log_counter = 0;
|
||||
Log_Write_PID(CH6_OPTFLOW_KP, tot_x_cm, p, i, d, of_roll, tuning_value);
|
||||
}
|
||||
}
|
||||
#endif // LOGGING_ENABLED == ENABLED
|
||||
}
|
||||
|
||||
// limit max angle
|
||||
of_roll = constrain(of_roll, -1000, 1000);
|
||||
|
||||
return control_roll+of_roll;
|
||||
#else
|
||||
return control_roll;
|
||||
@ -620,9 +640,11 @@ static int32_t
|
||||
get_of_pitch(int32_t control_pitch)
|
||||
{
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
static int8_t log_counter = 0; // used to slow down logging of PID values to dataflash
|
||||
static float tot_y_cm = 0; // total distance from target
|
||||
static uint32_t last_of_pitch_update = 0;
|
||||
int32_t new_pitch = 0;
|
||||
int32_t p,i,d;
|
||||
|
||||
// check if new optflow data available
|
||||
if( optflow.last_update != last_of_pitch_update ) {
|
||||
@ -633,18 +655,36 @@ get_of_pitch(int32_t control_pitch)
|
||||
|
||||
// only stop roll if caller isn't modifying pitch
|
||||
if( control_pitch == 0 && current_loc.alt < 1500 ) {
|
||||
new_pitch = g.pid_optflow_pitch.get_pid(tot_y_cm, 1.0); // we could use the last update time to calculate the time change
|
||||
p = g.pid_optflow_pitch.get_p(tot_y_cm);
|
||||
i = g.pid_optflow_pitch.get_i(tot_y_cm, 1.0); // we could use the last update time to calculate the time change
|
||||
d = g.pid_optflow_pitch.get_d(tot_y_cm, 1.0);
|
||||
new_pitch = p + i + d;
|
||||
}else{
|
||||
tot_y_cm = 0;
|
||||
g.pid_optflow_pitch.reset_I();
|
||||
p = 0; // for logging
|
||||
i = 0;
|
||||
d = 0;
|
||||
}
|
||||
|
||||
// limit amount of change
|
||||
of_pitch = constrain(new_pitch, (of_pitch-20), (of_pitch+20));
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
// log output if PID logging is on and we are tuning the rate P, I or D gains
|
||||
if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_OPTFLOW_KP || g.radio_tuning == CH6_OPTFLOW_KI || g.radio_tuning == CH6_OPTFLOW_KD) ) {
|
||||
log_counter++;
|
||||
if( log_counter >= 5 ) { // (update rate / desired output rate) = (100hz / 10hz) = 10
|
||||
log_counter = 0;
|
||||
Log_Write_PID(CH6_OPTFLOW_KP+100, tot_y_cm, p, i, d, of_pitch, tuning_value);
|
||||
}
|
||||
}
|
||||
#endif // LOGGING_ENABLED == ENABLED
|
||||
}
|
||||
|
||||
// limit max angle
|
||||
of_pitch = constrain(of_pitch, -1000, 1000);
|
||||
|
||||
return control_pitch+of_pitch;
|
||||
#else
|
||||
return control_pitch;
|
||||
|
@ -43,6 +43,19 @@ const struct Menu::command log_menu_commands[] PROGMEM = {
|
||||
{"disable", select_logs}
|
||||
};
|
||||
|
||||
static int32_t get_int(float f)
|
||||
{
|
||||
float_int.float_value = f;
|
||||
return float_int.int_value;
|
||||
}
|
||||
|
||||
static float get_float(int32_t i)
|
||||
{
|
||||
float_int.int_value = i;
|
||||
return float_int.float_value;
|
||||
}
|
||||
|
||||
|
||||
// A Macro to create the Menu
|
||||
MENU2(log_menu, "Log", log_menu_commands, print_log_menu);
|
||||
|
||||
@ -278,26 +291,21 @@ static void Log_Write_Raw()
|
||||
Vector3f accel = imu.get_accel();
|
||||
//Vector3f accel_filt = imu.get_accel_filtered();
|
||||
|
||||
gyro *= t7; // Scale up for storage as long integers
|
||||
accel *= t7;
|
||||
//gyro *= t7; // Scale up for storage as long integers
|
||||
//accel *= t7;
|
||||
//accel_filt *= t7;
|
||||
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_RAW_MSG);
|
||||
|
||||
DataFlash.WriteLong(gyro.x);
|
||||
DataFlash.WriteLong(gyro.y);
|
||||
DataFlash.WriteLong(gyro.z);
|
||||
DataFlash.WriteLong(get_int(gyro.x));
|
||||
DataFlash.WriteLong(get_int(gyro.y));
|
||||
DataFlash.WriteLong(get_int(gyro.z));
|
||||
|
||||
|
||||
//DataFlash.WriteLong(accels_rot.x * t7);
|
||||
//DataFlash.WriteLong(accels_rot.y * t7);
|
||||
//DataFlash.WriteLong(accels_rot.z * t7);
|
||||
|
||||
DataFlash.WriteLong(accel.x);
|
||||
DataFlash.WriteLong(accel.y);
|
||||
DataFlash.WriteLong(accel.z);
|
||||
DataFlash.WriteLong(get_int(accel.x));
|
||||
DataFlash.WriteLong(get_int(accel.y));
|
||||
DataFlash.WriteLong(get_int(accel.z));
|
||||
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
@ -308,9 +316,9 @@ static void Log_Read_Raw()
|
||||
float logvar;
|
||||
Serial.printf_P(PSTR("RAW,"));
|
||||
for (int y = 0; y < 6; y++) {
|
||||
logvar = (float)DataFlash.ReadLong() / t7;
|
||||
logvar = get_float(DataFlash.ReadLong());
|
||||
Serial.print(logvar);
|
||||
Serial.print(",");
|
||||
Serial.print(", ");
|
||||
}
|
||||
Serial.println(" ");
|
||||
}
|
||||
@ -764,7 +772,13 @@ static void Log_Read_Startup()
|
||||
|
||||
static void Log_Write_Data(int8_t _type, float _data)
|
||||
{
|
||||
Log_Write_Data(_type, (int32_t)(_data * 1000));
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_DATA_MSG);
|
||||
DataFlash.WriteByte(_type);
|
||||
DataFlash.WriteByte(1);
|
||||
DataFlash.WriteLong(get_int(_data));
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
|
||||
static void Log_Write_Data(int8_t _type, int32_t _data)
|
||||
@ -773,6 +787,7 @@ static void Log_Write_Data(int8_t _type, int32_t _data)
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_DATA_MSG);
|
||||
DataFlash.WriteByte(_type);
|
||||
DataFlash.WriteByte(0);
|
||||
DataFlash.WriteLong(_data);
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
@ -781,8 +796,15 @@ static void Log_Write_Data(int8_t _type, int32_t _data)
|
||||
static void Log_Read_Data()
|
||||
{
|
||||
int8_t temp1 = DataFlash.ReadByte();
|
||||
int32_t temp2 = DataFlash.ReadLong();
|
||||
Serial.printf_P(PSTR("DATA: %d, %ld\n"), temp1, temp2);
|
||||
int8_t temp2 = DataFlash.ReadByte();
|
||||
|
||||
if(temp2 == 1){
|
||||
float temp3 = get_float(DataFlash.ReadLong());
|
||||
Serial.printf_P(PSTR("DATA: %d, %1.6f\n"), temp1, temp3);
|
||||
}else{
|
||||
int32_t temp3 = DataFlash.ReadLong();
|
||||
Serial.printf_P(PSTR("DATA: %d, %ld\n"), temp1, temp3);
|
||||
}
|
||||
}
|
||||
|
||||
// Write an PID packet. Total length : 28 bytes
|
||||
|
@ -112,7 +112,11 @@
|
||||
|
||||
// default RC speed in Hz if INSTANT_PWM is not used
|
||||
#ifndef RC_FAST_SPEED
|
||||
# define RC_FAST_SPEED 490
|
||||
# if FRAME_CONFIG == HELI_FRAME
|
||||
# define RC_FAST_SPEED 125
|
||||
# else
|
||||
# define RC_FAST_SPEED 490
|
||||
# endif
|
||||
#endif
|
||||
|
||||
// LED and IO Pins
|
||||
@ -140,7 +144,7 @@
|
||||
# define PUSHBUTTON_PIN (-1)
|
||||
# define CLI_SLIDER_ENABLED DISABLED
|
||||
# define USB_MUX_PIN 23
|
||||
# define OPTFLOW_CS_PIN A6
|
||||
# define OPTFLOW_CS_PIN A3
|
||||
# define BATTERY_PIN_1 1
|
||||
# define CURRENT_PIN_1 2
|
||||
#endif
|
||||
|
@ -146,7 +146,7 @@
|
||||
// Attitude
|
||||
#define CH6_STABILIZE_KP 1
|
||||
#define CH6_STABILIZE_KI 2
|
||||
#define CH6_STABILIZE_KD 29
|
||||
#define CH6_STABILIZE_KD 29 // duplicate with CH6_DAMP
|
||||
#define CH6_YAW_KP 3
|
||||
#define CH6_YAW_KI 24
|
||||
// Rate
|
||||
@ -173,7 +173,7 @@
|
||||
// altitude controller
|
||||
#define CH6_THR_HOLD_KP 14
|
||||
#define CH6_Z_GAIN 15
|
||||
#define CH6_DAMP 16
|
||||
#define CH6_DAMP 16 // duplicate with CH6_YAW_RATE_KD
|
||||
|
||||
// optical flow controller
|
||||
#define CH6_OPTFLOW_KP 17
|
||||
|
@ -152,7 +152,7 @@
|
||||
</Reference>
|
||||
<Reference Include="Microsoft.DirectX.DirectInput, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<Private>True</Private>
|
||||
<Private>False</Private>
|
||||
</Reference>
|
||||
<Reference Include="Microsoft.Dynamic">
|
||||
</Reference>
|
||||
@ -240,6 +240,12 @@
|
||||
<Compile Include="Controls\BackstageView\BackStageViewMenuPanel.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\ConnectionControl.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\ConnectionControl.Designer.cs">
|
||||
<DependentUpon>ConnectionControl.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Controls\ConfigPanel.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
@ -256,6 +262,9 @@
|
||||
<Compile Include="Controls\ProgressReporterDialogue.designer.cs">
|
||||
<DependentUpon>ProgressReporterDialogue.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Controls\ToolStripConnectionControl.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibrationQuad.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
@ -561,6 +570,9 @@
|
||||
<EmbeddedResource Include="Controls\BackstageView\BackstageView.resx">
|
||||
<DependentUpon>BackstageView.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Controls\ConnectionControl.resx">
|
||||
<DependentUpon>ConnectionControl.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Controls\ConfigPanel.resx">
|
||||
<DependentUpon>ConfigPanel.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
|
@ -105,8 +105,9 @@ namespace ArdupilotMega
|
||||
float cog = -1;
|
||||
float target = -1;
|
||||
float nav_bearing = -1;
|
||||
public GMapControl MainMap;
|
||||
|
||||
public GMapMarkerPlane(PointLatLng p, float heading, float cog, float nav_bearing,float target)
|
||||
public GMapMarkerPlane(PointLatLng p, float heading, float cog, float nav_bearing,float target, GMapControl map)
|
||||
: base(p)
|
||||
{
|
||||
this.heading = heading;
|
||||
@ -114,6 +115,7 @@ namespace ArdupilotMega
|
||||
this.target = target;
|
||||
this.nav_bearing = nav_bearing;
|
||||
Size = SizeSt;
|
||||
MainMap = map;
|
||||
}
|
||||
|
||||
public override void OnRender(Graphics g)
|
||||
@ -137,7 +139,11 @@ namespace ArdupilotMega
|
||||
|
||||
float desired_lead_dist = 100;
|
||||
|
||||
float alpha = (desired_lead_dist / MainV2.cs.radius) * rad2deg;
|
||||
|
||||
double width = (MainMap.Manager.GetDistance(MainMap.FromLocalToLatLng(0, 0), MainMap.FromLocalToLatLng(MainMap.Width, 0)) * 1000.0);
|
||||
double m2pixelwidth = MainMap.Width / width;
|
||||
|
||||
float alpha = ((desired_lead_dist * (float)m2pixelwidth) / MainV2.cs.radius) * rad2deg;
|
||||
|
||||
if (MainV2.cs.radius < 0)
|
||||
{
|
||||
@ -663,7 +669,7 @@ namespace ArdupilotMega
|
||||
while (dataStream.CanRead && bytes > 0)
|
||||
{
|
||||
Application.DoEvents();
|
||||
log.Info(saveto + " " + bytes);
|
||||
log.Debug(saveto + " " + bytes);
|
||||
int len = dataStream.Read(buf1, 0, buf1.Length);
|
||||
bytes -= len;
|
||||
fs.Write(buf1, 0, len);
|
||||
|
88
Tools/ArdupilotMegaPlanner/Controls/ConnectionControl.Designer.cs
generated
Normal file
88
Tools/ArdupilotMegaPlanner/Controls/ConnectionControl.Designer.cs
generated
Normal file
@ -0,0 +1,88 @@
|
||||
namespace ArdupilotMega.Controls
|
||||
{
|
||||
partial class ConnectionControl
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Component Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.cmb_Baud = new System.Windows.Forms.ComboBox();
|
||||
this.cmb_ConnectionType = new System.Windows.Forms.ComboBox();
|
||||
this.cmb_Connection = new System.Windows.Forms.ComboBox();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// cmb_Baud
|
||||
//
|
||||
this.cmb_Baud.FormattingEnabled = true;
|
||||
this.cmb_Baud.Location = new System.Drawing.Point(130, 12);
|
||||
this.cmb_Baud.Name = "cmb_Baud";
|
||||
this.cmb_Baud.Size = new System.Drawing.Size(70, 21);
|
||||
this.cmb_Baud.TabIndex = 0;
|
||||
this.cmb_Baud.Items.AddRange(new object[] {
|
||||
"4800",
|
||||
"9600",
|
||||
"14400",
|
||||
"19200",
|
||||
"28800",
|
||||
"38400",
|
||||
"57600",
|
||||
"115200"});
|
||||
//
|
||||
// cmb_ConnectionType
|
||||
//
|
||||
this.cmb_ConnectionType.FormattingEnabled = true;
|
||||
this.cmb_ConnectionType.Location = new System.Drawing.Point(79, 39);
|
||||
this.cmb_ConnectionType.Name = "cmb_ConnectionType";
|
||||
this.cmb_ConnectionType.Size = new System.Drawing.Size(121, 21);
|
||||
this.cmb_ConnectionType.TabIndex = 1;
|
||||
//
|
||||
// cmb_Connection
|
||||
//
|
||||
this.cmb_Connection.FormattingEnabled = true;
|
||||
this.cmb_Connection.Location = new System.Drawing.Point(3, 12);
|
||||
this.cmb_Connection.Name = "cmb_Connection";
|
||||
this.cmb_Connection.Size = new System.Drawing.Size(121, 21);
|
||||
this.cmb_Connection.TabIndex = 2;
|
||||
//
|
||||
// ConnectionControl
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.cmb_Connection);
|
||||
this.Controls.Add(this.cmb_ConnectionType);
|
||||
this.Controls.Add(this.cmb_Baud);
|
||||
this.Name = "ConnectionControl";
|
||||
this.Size = new System.Drawing.Size(211, 75);
|
||||
this.ResumeLayout(false);
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.ComboBox cmb_Baud;
|
||||
private System.Windows.Forms.ComboBox cmb_ConnectionType;
|
||||
private System.Windows.Forms.ComboBox cmb_Connection;
|
||||
}
|
||||
}
|
23
Tools/ArdupilotMegaPlanner/Controls/ConnectionControl.cs
Normal file
23
Tools/ArdupilotMegaPlanner/Controls/ConnectionControl.cs
Normal file
@ -0,0 +1,23 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArdupilotMega.Controls
|
||||
{
|
||||
public partial class ConnectionControl : UserControl
|
||||
{
|
||||
public ConnectionControl()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
public ComboBox CMB_baudrate { get { return this.cmb_Baud; } }
|
||||
public ComboBox CMB_serialport { get { return this.cmb_Connection; } }
|
||||
public ComboBox TOOL_APMFirmware { get { return this.cmb_ConnectionType; } }
|
||||
}
|
||||
}
|
120
Tools/ArdupilotMegaPlanner/Controls/ConnectionControl.resx
Normal file
120
Tools/ArdupilotMegaPlanner/Controls/ConnectionControl.resx
Normal file
@ -0,0 +1,120 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
</root>
|
120
Tools/ArdupilotMegaPlanner/Controls/ConnectionToolStripItem.resx
Normal file
120
Tools/ArdupilotMegaPlanner/Controls/ConnectionToolStripItem.resx
Normal file
@ -0,0 +1,120 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
</root>
|
@ -0,0 +1,17 @@
|
||||
using System.Windows.Forms;
|
||||
namespace ArdupilotMega.Controls
|
||||
{
|
||||
public class ToolStripConnectionControl : ToolStripControlHost
|
||||
{
|
||||
// Call the base constructor passing in a MonthCalendar instance.
|
||||
public ToolStripConnectionControl()
|
||||
: base(new ConnectionControl())
|
||||
{
|
||||
}
|
||||
|
||||
public ConnectionControl ConnectionControl
|
||||
{
|
||||
get { return Control as ConnectionControl; }
|
||||
}
|
||||
}
|
||||
}
|
@ -47,34 +47,34 @@
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.5.3 Quad</name>
|
||||
<name>ArduCopter V2.5.4 Quad</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG QUAD_FRAME
|
||||
|
||||
</desc>
|
||||
<format_version>117</format_version>
|
||||
<format_version>118</format_version>
|
||||
</Firmware>
|
||||
<Firmware>
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.5.3 Tri</name>
|
||||
<name>ArduCopter V2.5.4 Tri</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG TRI_FRAME
|
||||
|
||||
</desc>
|
||||
<format_version>117</format_version>
|
||||
<format_version>118</format_version>
|
||||
</Firmware>
|
||||
<Firmware>
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.5.3 Hexa X</name>
|
||||
<name>ArduCopter V2.5.4 Hexa X</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG HEXA_FRAME
|
||||
|
||||
</desc>
|
||||
<format_version>117</format_version>
|
||||
<format_version>118</format_version>
|
||||
</Firmware>
|
||||
<Firmware>
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
|
||||
@ -91,34 +91,33 @@
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.5.3 Octa V</name>
|
||||
<name>ArduCopter V2.5.4 Octa V</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG OCTA_FRAME
|
||||
#define FRAME_ORIENTATION V_FRAME
|
||||
|
||||
</desc>
|
||||
<format_version>117</format_version>
|
||||
<format_version>118</format_version>
|
||||
</Firmware>
|
||||
<Firmware>
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.5.3 Octa X</name>
|
||||
<name>ArduCopter V2.5.4 Octa X</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG OCTA_FRAME
|
||||
|
||||
</desc>
|
||||
<format_version>117</format_version>
|
||||
<format_version>118</format_version>
|
||||
</Firmware>
|
||||
<Firmware>
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.5.3 Heli (2560 only)</name>
|
||||
<name>ArduCopter V2.5.4 Heli (2560 only)</name>
|
||||
<desc>
|
||||
#define AUTO_RESET_LOITER 0
|
||||
#define FRAME_CONFIG HELI_FRAME
|
||||
#define INSTANT_PWM ENABLED
|
||||
|
||||
// DEFAULT PIDS
|
||||
|
||||
@ -156,13 +155,13 @@
|
||||
#define NAV_LOITER_IMAX 10
|
||||
|
||||
</desc>
|
||||
<format_version>117</format_version>
|
||||
<format_version>118</format_version>
|
||||
</Firmware>
|
||||
<Firmware>
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.5.3 Quad Hil</name>
|
||||
<name>ArduCopter V2.5.4 Quad Hil</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG QUAD_FRAME
|
||||
#define FRAME_ORIENTATION PLUS_FRAME
|
||||
@ -172,13 +171,13 @@
|
||||
|
||||
|
||||
</desc>
|
||||
<format_version>117</format_version>
|
||||
<format_version>118</format_version>
|
||||
</Firmware>
|
||||
<Firmware>
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.5.3 Heli Hil</name>
|
||||
<name>ArduCopter V2.5.4 Heli Hil</name>
|
||||
<desc>
|
||||
|
||||
#define HIL_MODE HIL_MODE_ATTITUDE
|
||||
@ -224,6 +223,6 @@
|
||||
|
||||
|
||||
</desc>
|
||||
<format_version>117</format_version>
|
||||
<format_version>118</format_version>
|
||||
</Firmware>
|
||||
</options>
|
||||
|
@ -69,7 +69,7 @@ namespace ArdupilotMega.GCSViews
|
||||
XTRK_GAIN_SC1.Name = "XTRK_GAIN_SC";
|
||||
|
||||
// enable disable relevbant hardware tabs
|
||||
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
|
||||
{
|
||||
this.ConfigTabs.SuspendLayout();
|
||||
ConfigTabs.SelectedIndex = 0;
|
||||
@ -656,7 +656,7 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
StreamWriter sw = new StreamWriter(sfd.OpenFile());
|
||||
string input = DateTime.Now + " Frame : + | Arducopter Kit | Kit motors";
|
||||
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
|
||||
{
|
||||
input = DateTime.Now + " Plane: Skywalker";
|
||||
}
|
||||
@ -986,7 +986,7 @@ namespace ArdupilotMega.GCSViews
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.config["distunits"] = CMB_distunits.Text;
|
||||
MainV2.instance.changeunits();
|
||||
MainV2.instance.ChangeUnits();
|
||||
}
|
||||
|
||||
private void CMB_speedunits_SelectedIndexChanged(object sender, EventArgs e)
|
||||
@ -994,7 +994,7 @@ namespace ArdupilotMega.GCSViews
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.config["speedunits"] = CMB_speedunits.Text;
|
||||
MainV2.instance.changeunits();
|
||||
MainV2.instance.ChangeUnits();
|
||||
}
|
||||
|
||||
|
||||
|
@ -237,8 +237,9 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
((MyButton)sender).Enabled = true;
|
||||
startup = true;
|
||||
|
||||
// AR todo: fix this up
|
||||
//Configuration_Load(null, null);
|
||||
|
||||
|
||||
startup = false;
|
||||
}
|
||||
|
||||
private void CHK_speechbattery_CheckedChanged(object sender, EventArgs e)
|
||||
@ -276,7 +277,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.config["distunits"] = CMB_distunits.Text;
|
||||
MainV2.instance.changeunits();
|
||||
MainV2.instance.ChangeUnits();
|
||||
}
|
||||
|
||||
private void CMB_speedunits_SelectedIndexChanged(object sender, EventArgs e)
|
||||
@ -284,7 +285,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.config["speedunits"] = CMB_speedunits.Text;
|
||||
MainV2.instance.changeunits();
|
||||
MainV2.instance.ChangeUnits();
|
||||
}
|
||||
|
||||
private void CMB_rateattitude_SelectedIndexChanged(object sender, EventArgs e)
|
||||
|
@ -162,7 +162,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
StreamWriter sw = new StreamWriter(sfd.OpenFile());
|
||||
string input = DateTime.Now + " Frame : + | Arducopter Kit | Kit motors";
|
||||
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
|
||||
{
|
||||
input = DateTime.Now + " Plane: Skywalker";
|
||||
}
|
||||
|
@ -31,21 +31,21 @@
|
||||
this.components = new System.ComponentModel.Container();
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigTradHeli));
|
||||
this.groupBox5 = new System.Windows.Forms.GroupBox();
|
||||
this.H1_ENABLE = new System.Windows.Forms.RadioButton();
|
||||
this.H_SWASH_TYPE = new System.Windows.Forms.RadioButton();
|
||||
this.CCPM = new System.Windows.Forms.RadioButton();
|
||||
this.BUT_swash_manual = new ArdupilotMega.MyButton();
|
||||
this.label41 = new System.Windows.Forms.Label();
|
||||
this.groupBox3 = new System.Windows.Forms.GroupBox();
|
||||
this.label46 = new System.Windows.Forms.Label();
|
||||
this.label45 = new System.Windows.Forms.Label();
|
||||
this.GYR_ENABLE = new System.Windows.Forms.CheckBox();
|
||||
this.GYR_GAIN = new System.Windows.Forms.TextBox();
|
||||
this.H_GYR_ENABLE = new System.Windows.Forms.CheckBox();
|
||||
this.H_GYR_GAIN = new System.Windows.Forms.TextBox();
|
||||
this.BUT_HS4save = new ArdupilotMega.MyButton();
|
||||
this.label21 = new System.Windows.Forms.Label();
|
||||
this.COL_MIN = new System.Windows.Forms.TextBox();
|
||||
this.H_COL_MIN = new System.Windows.Forms.TextBox();
|
||||
this.groupBox1 = new System.Windows.Forms.GroupBox();
|
||||
this.COL_MID = new System.Windows.Forms.TextBox();
|
||||
this.COL_MAX = new System.Windows.Forms.TextBox();
|
||||
this.H_COL_MID = new System.Windows.Forms.TextBox();
|
||||
this.H_COL_MAX = new System.Windows.Forms.TextBox();
|
||||
this.BUT_0collective = new ArdupilotMega.MyButton();
|
||||
this.groupBox2 = new System.Windows.Forms.GroupBox();
|
||||
this.label24 = new System.Windows.Forms.Label();
|
||||
@ -60,17 +60,17 @@
|
||||
this.label37 = new System.Windows.Forms.Label();
|
||||
this.label36 = new System.Windows.Forms.Label();
|
||||
this.label26 = new System.Windows.Forms.Label();
|
||||
this.PIT_MAX = new System.Windows.Forms.TextBox();
|
||||
this.H_PIT_MAX = new System.Windows.Forms.TextBox();
|
||||
this.label25 = new System.Windows.Forms.Label();
|
||||
this.ROL_MAX = new System.Windows.Forms.TextBox();
|
||||
this.H_ROL_MAX = new System.Windows.Forms.TextBox();
|
||||
this.label23 = new System.Windows.Forms.Label();
|
||||
this.label22 = new System.Windows.Forms.Label();
|
||||
this.label20 = new System.Windows.Forms.Label();
|
||||
this.label19 = new System.Windows.Forms.Label();
|
||||
this.label18 = new System.Windows.Forms.Label();
|
||||
this.SV3_POS = new System.Windows.Forms.TextBox();
|
||||
this.SV2_POS = new System.Windows.Forms.TextBox();
|
||||
this.SV1_POS = new System.Windows.Forms.TextBox();
|
||||
this.H_SV3_POS = new System.Windows.Forms.TextBox();
|
||||
this.H_SV2_POS = new System.Windows.Forms.TextBox();
|
||||
this.H_SV1_POS = new System.Windows.Forms.TextBox();
|
||||
this.HS3_REV = new System.Windows.Forms.CheckBox();
|
||||
this.HS2_REV = new System.Windows.Forms.CheckBox();
|
||||
this.HS1_REV = new System.Windows.Forms.CheckBox();
|
||||
@ -97,19 +97,19 @@
|
||||
//
|
||||
// groupBox5
|
||||
//
|
||||
this.groupBox5.Controls.Add(this.H1_ENABLE);
|
||||
this.groupBox5.Controls.Add(this.H_SWASH_TYPE);
|
||||
this.groupBox5.Controls.Add(this.CCPM);
|
||||
resources.ApplyResources(this.groupBox5, "groupBox5");
|
||||
this.groupBox5.Name = "groupBox5";
|
||||
this.groupBox5.TabStop = false;
|
||||
//
|
||||
// H1_ENABLE
|
||||
// H_SWASH_TYPE
|
||||
//
|
||||
resources.ApplyResources(this.H1_ENABLE, "H1_ENABLE");
|
||||
this.H1_ENABLE.Name = "H1_ENABLE";
|
||||
this.H1_ENABLE.TabStop = true;
|
||||
this.H1_ENABLE.UseVisualStyleBackColor = true;
|
||||
this.H1_ENABLE.CheckedChanged += new System.EventHandler(this.H1_ENABLE_CheckedChanged);
|
||||
resources.ApplyResources(this.H_SWASH_TYPE, "H_SWASH_TYPE");
|
||||
this.H_SWASH_TYPE.Name = "H_SWASH_TYPE";
|
||||
this.H_SWASH_TYPE.TabStop = true;
|
||||
this.H_SWASH_TYPE.UseVisualStyleBackColor = true;
|
||||
this.H_SWASH_TYPE.CheckedChanged += new System.EventHandler(this.H_SWASH_TYPE_CheckedChanged);
|
||||
//
|
||||
// CCPM
|
||||
//
|
||||
@ -134,8 +134,8 @@
|
||||
//
|
||||
this.groupBox3.Controls.Add(this.label46);
|
||||
this.groupBox3.Controls.Add(this.label45);
|
||||
this.groupBox3.Controls.Add(this.GYR_ENABLE);
|
||||
this.groupBox3.Controls.Add(this.GYR_GAIN);
|
||||
this.groupBox3.Controls.Add(this.H_GYR_ENABLE);
|
||||
this.groupBox3.Controls.Add(this.H_GYR_GAIN);
|
||||
resources.ApplyResources(this.groupBox3, "groupBox3");
|
||||
this.groupBox3.Name = "groupBox3";
|
||||
this.groupBox3.TabStop = false;
|
||||
@ -150,18 +150,18 @@
|
||||
resources.ApplyResources(this.label45, "label45");
|
||||
this.label45.Name = "label45";
|
||||
//
|
||||
// GYR_ENABLE
|
||||
// H_GYR_ENABLE
|
||||
//
|
||||
resources.ApplyResources(this.GYR_ENABLE, "GYR_ENABLE");
|
||||
this.GYR_ENABLE.Name = "GYR_ENABLE";
|
||||
this.GYR_ENABLE.UseVisualStyleBackColor = true;
|
||||
this.GYR_ENABLE.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged);
|
||||
resources.ApplyResources(this.H_GYR_ENABLE, "H_GYR_ENABLE");
|
||||
this.H_GYR_ENABLE.Name = "H_GYR_ENABLE";
|
||||
this.H_GYR_ENABLE.UseVisualStyleBackColor = true;
|
||||
this.H_GYR_ENABLE.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged);
|
||||
//
|
||||
// GYR_GAIN
|
||||
// H_GYR_GAIN
|
||||
//
|
||||
resources.ApplyResources(this.GYR_GAIN, "GYR_GAIN");
|
||||
this.GYR_GAIN.Name = "GYR_GAIN";
|
||||
this.GYR_GAIN.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating);
|
||||
resources.ApplyResources(this.H_GYR_GAIN, "H_GYR_GAIN");
|
||||
this.H_GYR_GAIN.Name = "H_GYR_GAIN";
|
||||
this.H_GYR_GAIN.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating);
|
||||
//
|
||||
// BUT_HS4save
|
||||
//
|
||||
@ -175,36 +175,36 @@
|
||||
resources.ApplyResources(this.label21, "label21");
|
||||
this.label21.Name = "label21";
|
||||
//
|
||||
// COL_MIN
|
||||
// H_COL_MIN
|
||||
//
|
||||
resources.ApplyResources(this.COL_MIN, "COL_MIN");
|
||||
this.COL_MIN.Name = "COL_MIN";
|
||||
resources.ApplyResources(this.H_COL_MIN, "H_COL_MIN");
|
||||
this.H_COL_MIN.Name = "H_COL_MIN";
|
||||
//
|
||||
// groupBox1
|
||||
//
|
||||
this.groupBox1.Controls.Add(this.label41);
|
||||
this.groupBox1.Controls.Add(this.label21);
|
||||
this.groupBox1.Controls.Add(this.COL_MIN);
|
||||
this.groupBox1.Controls.Add(this.COL_MID);
|
||||
this.groupBox1.Controls.Add(this.COL_MAX);
|
||||
this.groupBox1.Controls.Add(this.H_COL_MIN);
|
||||
this.groupBox1.Controls.Add(this.H_COL_MID);
|
||||
this.groupBox1.Controls.Add(this.H_COL_MAX);
|
||||
this.groupBox1.Controls.Add(this.BUT_0collective);
|
||||
resources.ApplyResources(this.groupBox1, "groupBox1");
|
||||
this.groupBox1.Name = "groupBox1";
|
||||
this.groupBox1.TabStop = false;
|
||||
//
|
||||
// COL_MID
|
||||
// H_COL_MID
|
||||
//
|
||||
resources.ApplyResources(this.COL_MID, "COL_MID");
|
||||
this.COL_MID.Name = "COL_MID";
|
||||
this.COL_MID.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
||||
resources.ApplyResources(this.H_COL_MID, "H_COL_MID");
|
||||
this.H_COL_MID.Name = "H_COL_MID";
|
||||
this.H_COL_MID.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
||||
//
|
||||
// COL_MAX
|
||||
// H_COL_MAX
|
||||
//
|
||||
resources.ApplyResources(this.COL_MAX, "COL_MAX");
|
||||
this.COL_MAX.Name = "COL_MAX";
|
||||
this.COL_MAX.Enter += new System.EventHandler(this.COL_MAX__Enter);
|
||||
this.COL_MAX.Leave += new System.EventHandler(this.COL_MAX__Leave);
|
||||
this.COL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
||||
resources.ApplyResources(this.H_COL_MAX, "H_COL_MAX");
|
||||
this.H_COL_MAX.Name = "H_COL_MAX";
|
||||
this.H_COL_MAX.Enter += new System.EventHandler(this.COL_MAX__Enter);
|
||||
this.H_COL_MAX.Leave += new System.EventHandler(this.COL_MAX__Leave);
|
||||
this.H_COL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
||||
//
|
||||
// BUT_0collective
|
||||
//
|
||||
@ -334,22 +334,22 @@
|
||||
resources.ApplyResources(this.label26, "label26");
|
||||
this.label26.Name = "label26";
|
||||
//
|
||||
// PIT_MAX
|
||||
// H_PIT_MAX
|
||||
//
|
||||
resources.ApplyResources(this.PIT_MAX, "PIT_MAX");
|
||||
this.PIT_MAX.Name = "PIT_MAX";
|
||||
this.PIT_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating);
|
||||
resources.ApplyResources(this.H_PIT_MAX, "H_PIT_MAX");
|
||||
this.H_PIT_MAX.Name = "H_PIT_MAX";
|
||||
this.H_PIT_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating);
|
||||
//
|
||||
// label25
|
||||
//
|
||||
resources.ApplyResources(this.label25, "label25");
|
||||
this.label25.Name = "label25";
|
||||
//
|
||||
// ROL_MAX
|
||||
// H_ROL_MAX
|
||||
//
|
||||
resources.ApplyResources(this.ROL_MAX, "ROL_MAX");
|
||||
this.ROL_MAX.Name = "ROL_MAX";
|
||||
this.ROL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating);
|
||||
resources.ApplyResources(this.H_ROL_MAX, "H_ROL_MAX");
|
||||
this.H_ROL_MAX.Name = "H_ROL_MAX";
|
||||
this.H_ROL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating);
|
||||
//
|
||||
// label23
|
||||
//
|
||||
@ -376,23 +376,23 @@
|
||||
resources.ApplyResources(this.label18, "label18");
|
||||
this.label18.Name = "label18";
|
||||
//
|
||||
// SV3_POS
|
||||
// H_SV3_POS
|
||||
//
|
||||
resources.ApplyResources(this.SV3_POS, "SV3_POS");
|
||||
this.SV3_POS.Name = "SV3_POS";
|
||||
this.SV3_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos3_Validating);
|
||||
resources.ApplyResources(this.H_SV3_POS, "H_SV3_POS");
|
||||
this.H_SV3_POS.Name = "H_SV3_POS";
|
||||
this.H_SV3_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos3_Validating);
|
||||
//
|
||||
// SV2_POS
|
||||
// H_SV2_POS
|
||||
//
|
||||
resources.ApplyResources(this.SV2_POS, "SV2_POS");
|
||||
this.SV2_POS.Name = "SV2_POS";
|
||||
this.SV2_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos2_Validating);
|
||||
resources.ApplyResources(this.H_SV2_POS, "H_SV2_POS");
|
||||
this.H_SV2_POS.Name = "H_SV2_POS";
|
||||
this.H_SV2_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos2_Validating);
|
||||
//
|
||||
// SV1_POS
|
||||
// H_SV1_POS
|
||||
//
|
||||
resources.ApplyResources(this.SV1_POS, "SV1_POS");
|
||||
this.SV1_POS.Name = "SV1_POS";
|
||||
this.SV1_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos1_Validating);
|
||||
resources.ApplyResources(this.H_SV1_POS, "H_SV1_POS");
|
||||
this.H_SV1_POS.Name = "H_SV1_POS";
|
||||
this.H_SV1_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos1_Validating);
|
||||
//
|
||||
// HS3_REV
|
||||
//
|
||||
@ -665,17 +665,17 @@
|
||||
this.Controls.Add(this.label37);
|
||||
this.Controls.Add(this.label36);
|
||||
this.Controls.Add(this.label26);
|
||||
this.Controls.Add(this.PIT_MAX);
|
||||
this.Controls.Add(this.H_PIT_MAX);
|
||||
this.Controls.Add(this.label25);
|
||||
this.Controls.Add(this.ROL_MAX);
|
||||
this.Controls.Add(this.H_ROL_MAX);
|
||||
this.Controls.Add(this.label23);
|
||||
this.Controls.Add(this.label22);
|
||||
this.Controls.Add(this.label20);
|
||||
this.Controls.Add(this.label19);
|
||||
this.Controls.Add(this.label18);
|
||||
this.Controls.Add(this.SV3_POS);
|
||||
this.Controls.Add(this.SV2_POS);
|
||||
this.Controls.Add(this.SV1_POS);
|
||||
this.Controls.Add(this.H_SV3_POS);
|
||||
this.Controls.Add(this.H_SV2_POS);
|
||||
this.Controls.Add(this.H_SV1_POS);
|
||||
this.Controls.Add(this.HS3_REV);
|
||||
this.Controls.Add(this.HS2_REV);
|
||||
this.Controls.Add(this.HS1_REV);
|
||||
@ -707,21 +707,21 @@
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.GroupBox groupBox5;
|
||||
private System.Windows.Forms.RadioButton H1_ENABLE;
|
||||
private System.Windows.Forms.RadioButton H_SWASH_TYPE;
|
||||
private System.Windows.Forms.RadioButton CCPM;
|
||||
private MyButton BUT_swash_manual;
|
||||
private System.Windows.Forms.Label label41;
|
||||
private System.Windows.Forms.GroupBox groupBox3;
|
||||
private System.Windows.Forms.Label label46;
|
||||
private System.Windows.Forms.Label label45;
|
||||
private System.Windows.Forms.CheckBox GYR_ENABLE;
|
||||
private System.Windows.Forms.TextBox GYR_GAIN;
|
||||
private System.Windows.Forms.CheckBox H_GYR_ENABLE;
|
||||
private System.Windows.Forms.TextBox H_GYR_GAIN;
|
||||
private MyButton BUT_HS4save;
|
||||
private System.Windows.Forms.Label label21;
|
||||
private System.Windows.Forms.TextBox COL_MIN;
|
||||
private System.Windows.Forms.TextBox H_COL_MIN;
|
||||
private System.Windows.Forms.GroupBox groupBox1;
|
||||
private System.Windows.Forms.TextBox COL_MID;
|
||||
private System.Windows.Forms.TextBox COL_MAX;
|
||||
private System.Windows.Forms.TextBox H_COL_MID;
|
||||
private System.Windows.Forms.TextBox H_COL_MAX;
|
||||
private MyButton BUT_0collective;
|
||||
private System.Windows.Forms.GroupBox groupBox2;
|
||||
private System.Windows.Forms.Label label24;
|
||||
@ -736,17 +736,17 @@
|
||||
private System.Windows.Forms.Label label37;
|
||||
private System.Windows.Forms.Label label36;
|
||||
private System.Windows.Forms.Label label26;
|
||||
private System.Windows.Forms.TextBox PIT_MAX;
|
||||
private System.Windows.Forms.TextBox H_PIT_MAX;
|
||||
private System.Windows.Forms.Label label25;
|
||||
private System.Windows.Forms.TextBox ROL_MAX;
|
||||
private System.Windows.Forms.TextBox H_ROL_MAX;
|
||||
private System.Windows.Forms.Label label23;
|
||||
private System.Windows.Forms.Label label22;
|
||||
private System.Windows.Forms.Label label20;
|
||||
private System.Windows.Forms.Label label19;
|
||||
private System.Windows.Forms.Label label18;
|
||||
private System.Windows.Forms.TextBox SV3_POS;
|
||||
private System.Windows.Forms.TextBox SV2_POS;
|
||||
private System.Windows.Forms.TextBox SV1_POS;
|
||||
private System.Windows.Forms.TextBox H_SV3_POS;
|
||||
private System.Windows.Forms.TextBox H_SV2_POS;
|
||||
private System.Windows.Forms.TextBox H_SV1_POS;
|
||||
private System.Windows.Forms.CheckBox HS3_REV;
|
||||
private System.Windows.Forms.CheckBox HS2_REV;
|
||||
private System.Windows.Forms.CheckBox HS1_REV;
|
||||
|
@ -22,65 +22,65 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
private void H1_ENABLE_CheckedChanged(object sender, EventArgs e)
|
||||
private void H_SWASH_TYPE_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["H1_ENABLE"] == null)
|
||||
if (MainV2.comPort.param["H_SWASH_TYPE"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("H1_ENABLE", ((RadioButton)sender).Checked == true ? 1 : 0);
|
||||
MainV2.comPort.setParam("H_SWASH_TYPE", ((RadioButton)sender).Checked == true ? 1 : 0);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set H1_ENABLE Failed"); }
|
||||
catch { CustomMessageBox.Show("Set H_SWASH_TYPE Failed"); }
|
||||
}
|
||||
|
||||
private void BUT_swash_manual_Click(object sender, EventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
|
||||
if (MainV2.comPort.param["H_SV_MAN"].ToString() == "1")
|
||||
{
|
||||
MainV2.comPort.setParam("COL_MIN", int.Parse(COL_MIN.Text));
|
||||
MainV2.comPort.setParam("COL_MAX", int.Parse(COL_MAX.Text));
|
||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||
MainV2.comPort.setParam("H_COL_MIN", int.Parse(H_COL_MIN.Text));
|
||||
MainV2.comPort.setParam("H_COL_MAX", int.Parse(H_COL_MAX.Text));
|
||||
MainV2.comPort.setParam("H_SV_MAN", 0); // randy request - last
|
||||
BUT_swash_manual.Text = "Manual";
|
||||
|
||||
COL_MAX.Enabled = false;
|
||||
COL_MID.Enabled = false;
|
||||
COL_MIN.Enabled = false;
|
||||
H_COL_MAX.Enabled = false;
|
||||
H_COL_MID.Enabled = false;
|
||||
H_COL_MIN.Enabled = false;
|
||||
BUT_0collective.Enabled = false;
|
||||
}
|
||||
else
|
||||
{
|
||||
COL_MAX.Text = "1500";
|
||||
COL_MIN.Text = "1500";
|
||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||
H_COL_MAX.Text = "1500";
|
||||
H_COL_MIN.Text = "1500";
|
||||
MainV2.comPort.setParam("H_SV_MAN", 1); // randy request
|
||||
BUT_swash_manual.Text = "Save";
|
||||
|
||||
COL_MAX.Enabled = true;
|
||||
COL_MID.Enabled = true;
|
||||
COL_MIN.Enabled = true;
|
||||
H_COL_MAX.Enabled = true;
|
||||
H_COL_MID.Enabled = true;
|
||||
H_COL_MIN.Enabled = true;
|
||||
BUT_0collective.Enabled = true;
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Failed to set HSV_MAN"); }
|
||||
catch { CustomMessageBox.Show("Failed to set H_SV_MAN"); }
|
||||
}
|
||||
|
||||
private void BUT_HS4save_Click(object sender, EventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
|
||||
if (MainV2.comPort.param["H_SV_MAN"].ToString() == "1")
|
||||
{
|
||||
MainV2.comPort.setParam("HS4_MIN", int.Parse(HS4_MIN.Text));
|
||||
MainV2.comPort.setParam("HS4_MAX", int.Parse(HS4_MAX.Text));
|
||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||
MainV2.comPort.setParam("H_SV_MAN", 0); // randy request - last
|
||||
BUT_HS4save.Text = "Manual";
|
||||
|
||||
HS4_MAX.Enabled = false;
|
||||
@ -90,7 +90,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
HS4_MIN.Text = "1500";
|
||||
HS4_MAX.Text = "1500";
|
||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||
MainV2.comPort.setParam("H_SV_MAN", 1); // randy request
|
||||
BUT_HS4save.Text = "Save";
|
||||
|
||||
|
||||
@ -98,7 +98,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
HS4_MIN.Enabled = true;
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Failed to set HSV_MAN"); }
|
||||
catch { CustomMessageBox.Show("Failed to set H_SV_MAN"); }
|
||||
}
|
||||
|
||||
private void tabHeli_Click(object sender, EventArgs e)
|
||||
@ -122,10 +122,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
try
|
||||
{
|
||||
if (int.Parse(COL_MIN.Text) > HS3.minline)
|
||||
COL_MIN.Text = HS3.minline.ToString();
|
||||
if (int.Parse(COL_MAX.Text) < HS3.maxline)
|
||||
COL_MAX.Text = HS3.maxline.ToString();
|
||||
if (int.Parse(H_COL_MIN.Text) > HS3.minline)
|
||||
H_COL_MIN.Text = HS3.minline.ToString();
|
||||
if (int.Parse(H_COL_MAX.Text) < HS3.maxline)
|
||||
H_COL_MAX.Text = HS3.maxline.ToString();
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
@ -194,10 +194,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
|
||||
try
|
||||
{
|
||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||
MainV2.comPort.setParam("H_SV_MAN", 1); // randy request
|
||||
MainV2.comPort.setParam(((TextBox)sender).Name, test);
|
||||
System.Threading.Thread.Sleep(100);
|
||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||
MainV2.comPort.setParam("H_SV_MAN", 0); // randy request - last
|
||||
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
||||
@ -217,10 +217,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
|
||||
try
|
||||
{
|
||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||
MainV2.comPort.setParam("H_SV_MAN", 1); // randy request
|
||||
MainV2.comPort.setParam(((TextBox)sender).Name, test);
|
||||
System.Threading.Thread.Sleep(100);
|
||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||
MainV2.comPort.setParam("H_SV_MAN", 0); // randy request - last
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
||||
}
|
||||
@ -239,10 +239,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
|
||||
try
|
||||
{
|
||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||
MainV2.comPort.setParam("H_SV_MAN", 1); // randy request
|
||||
MainV2.comPort.setParam(((TextBox)sender).Name, test);
|
||||
System.Threading.Thread.Sleep(100);
|
||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||
MainV2.comPort.setParam("H_SV_MAN", 0); // randy request - last
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
||||
}
|
||||
@ -254,11 +254,11 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
try
|
||||
{
|
||||
|
||||
MainV2.comPort.setParam("COL_MID", MainV2.cs.ch3in);
|
||||
MainV2.comPort.setParam("H_COL_MID", MainV2.cs.ch3in);
|
||||
|
||||
COL_MID.Text = MainV2.comPort.param["COL_MID"].ToString();
|
||||
H_COL_MID.Text = MainV2.comPort.param["H_COL_MID"].ToString();
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set COL_MID_ failed"); }
|
||||
catch { CustomMessageBox.Show("Set H_COL_MID failed"); }
|
||||
}
|
||||
|
||||
private void HS1_REV_CheckedChanged(object sender, EventArgs e)
|
||||
@ -379,7 +379,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
this.Enabled = true;
|
||||
}
|
||||
|
||||
if (MainV2.comPort.param["GYR_ENABLE"] == null)
|
||||
if (MainV2.comPort.param["H_GYR_ENABLE"] == null)
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
@ -394,10 +394,10 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
startup = true;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param.ContainsKey("H1_ENABLE"))
|
||||
if (MainV2.comPort.param.ContainsKey("H_SWASH_TYPE"))
|
||||
{
|
||||
CCPM.Checked = MainV2.comPort.param["H1_ENABLE"].ToString() == "0" ? true : false;
|
||||
H1_ENABLE.Checked = !CCPM.Checked;
|
||||
CCPM.Checked = MainV2.comPort.param["H_SWASH_TYPE"].ToString() == "0" ? true : false;
|
||||
H_SWASH_TYPE.Checked = !CCPM.Checked;
|
||||
}
|
||||
|
||||
foreach (string value in MainV2.comPort.param.Keys)
|
||||
@ -453,7 +453,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
}
|
||||
catch { }
|
||||
|
||||
if (MainV2.comPort.param["HSV_MAN"] == null || MainV2.comPort.param["HSV_MAN"].ToString() == "0")
|
||||
if (MainV2.comPort.param["H_SV_MAN"] == null || MainV2.comPort.param["H_SV_MAN"].ToString() == "0")
|
||||
return;
|
||||
|
||||
if (HS3.minline == 0)
|
||||
@ -477,8 +477,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
try
|
||||
{
|
||||
HS3.minline = int.Parse(COL_MIN.Text);
|
||||
HS3.maxline = int.Parse(COL_MAX.Text);
|
||||
HS3.minline = int.Parse(H_COL_MIN.Text);
|
||||
HS3.maxline = int.Parse(H_COL_MAX.Text);
|
||||
HS4.maxline = int.Parse(HS4_MIN.Text);
|
||||
HS4.minline = int.Parse(HS4_MAX.Text);
|
||||
}
|
||||
|
@ -117,42 +117,36 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="H1_ENABLE.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="H1_ENABLE.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<data name="H1_ENABLE.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>67, 19</value>
|
||||
<data name="H_SWASH_TYPE.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>67, 15</value>
|
||||
</data>
|
||||
<data name="H1_ENABLE.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>39, 17</value>
|
||||
<data name="H_SWASH_TYPE.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>42, 24</value>
|
||||
</data>
|
||||
<data name="H1_ENABLE.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>137</value>
|
||||
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="H_SWASH_TYPE.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="H1_ENABLE.Text" xml:space="preserve">
|
||||
<data name="H_SWASH_TYPE.Text" xml:space="preserve">
|
||||
<value>H1</value>
|
||||
</data>
|
||||
<data name=">>H1_ENABLE.Name" xml:space="preserve">
|
||||
<value>H1_ENABLE</value>
|
||||
<data name=">>H_SWASH_TYPE.Name" xml:space="preserve">
|
||||
<value>H_SWASH_TYPE</value>
|
||||
</data>
|
||||
<data name=">>H1_ENABLE.Type" xml:space="preserve">
|
||||
<data name=">>H_SWASH_TYPE.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=">>H1_ENABLE.Parent" xml:space="preserve">
|
||||
<data name=">>H_SWASH_TYPE.Parent" xml:space="preserve">
|
||||
<value>groupBox5</value>
|
||||
</data>
|
||||
<data name=">>H1_ENABLE.ZOrder" xml:space="preserve">
|
||||
<data name=">>H_SWASH_TYPE.ZOrder" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="CCPM.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="CCPM.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
@ -223,7 +217,7 @@
|
||||
<value>BUT_swash_manual</value>
|
||||
</data>
|
||||
<data name=">>BUT_swash_manual.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BUT_swash_manual.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
@ -321,55 +315,55 @@
|
||||
<data name=">>label45.ZOrder" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="GYR_ENABLE.AutoSize" type="System.Boolean, mscorlib">
|
||||
<data name="H_GYR_ENABLE.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="GYR_ENABLE.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<data name="H_GYR_ENABLE.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="GYR_ENABLE.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<data name="H_GYR_ENABLE.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>57, 19</value>
|
||||
</data>
|
||||
<data name="GYR_ENABLE.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="H_GYR_ENABLE.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>15, 14</value>
|
||||
</data>
|
||||
<data name="GYR_ENABLE.TabIndex" type="System.Int32, mscorlib">
|
||||
<data name="H_GYR_ENABLE.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>118</value>
|
||||
</data>
|
||||
<data name=">>GYR_ENABLE.Name" xml:space="preserve">
|
||||
<value>GYR_ENABLE</value>
|
||||
<data name=">>H_GYR_ENABLE.Name" xml:space="preserve">
|
||||
<value>H_GYR_ENABLE</value>
|
||||
</data>
|
||||
<data name=">>GYR_ENABLE.Type" xml:space="preserve">
|
||||
<data name=">>H_GYR_ENABLE.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>GYR_ENABLE.Parent" xml:space="preserve">
|
||||
<data name=">>H_GYR_ENABLE.Parent" xml:space="preserve">
|
||||
<value>groupBox3</value>
|
||||
</data>
|
||||
<data name=">>GYR_ENABLE.ZOrder" xml:space="preserve">
|
||||
<data name=">>H_GYR_ENABLE.ZOrder" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<data name="H_GYR_GAIN.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>41, 35</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="H_GYR_GAIN.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>47, 20</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN.TabIndex" type="System.Int32, mscorlib">
|
||||
<data name="H_GYR_GAIN.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>119</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN.Text" xml:space="preserve">
|
||||
<data name="H_GYR_GAIN.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name=">>GYR_GAIN.Name" xml:space="preserve">
|
||||
<value>GYR_GAIN</value>
|
||||
<data name=">>H_GYR_GAIN.Name" xml:space="preserve">
|
||||
<value>H_GYR_GAIN</value>
|
||||
</data>
|
||||
<data name=">>GYR_GAIN.Type" xml:space="preserve">
|
||||
<data name=">>H_GYR_GAIN.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>GYR_GAIN.Parent" xml:space="preserve">
|
||||
<data name=">>H_GYR_GAIN.Parent" xml:space="preserve">
|
||||
<value>groupBox3</value>
|
||||
</data>
|
||||
<data name=">>GYR_GAIN.ZOrder" xml:space="preserve">
|
||||
<data name=">>H_GYR_GAIN.ZOrder" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="groupBox3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
@ -415,7 +409,7 @@
|
||||
<value>BUT_HS4save</value>
|
||||
</data>
|
||||
<data name=">>BUT_HS4save.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BUT_HS4save.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
@ -453,85 +447,85 @@
|
||||
<data name=">>label21.ZOrder" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="COL_MIN.Enabled" type="System.Boolean, mscorlib">
|
||||
<data name="H_COL_MIN.Enabled" type="System.Boolean, mscorlib">
|
||||
<value>False</value>
|
||||
</data>
|
||||
<data name="COL_MIN.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<data name="H_COL_MIN.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>18, 173</value>
|
||||
</data>
|
||||
<data name="COL_MIN.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="H_COL_MIN.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>43, 20</value>
|
||||
</data>
|
||||
<data name="COL_MIN.TabIndex" type="System.Int32, mscorlib">
|
||||
<data name="H_COL_MIN.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>119</value>
|
||||
</data>
|
||||
<data name="COL_MIN.Text" xml:space="preserve">
|
||||
<data name="H_COL_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name=">>COL_MIN.Name" xml:space="preserve">
|
||||
<value>COL_MIN</value>
|
||||
<data name=">>H_COL_MIN.Name" xml:space="preserve">
|
||||
<value>H_COL_MIN</value>
|
||||
</data>
|
||||
<data name=">>COL_MIN.Type" xml:space="preserve">
|
||||
<data name=">>H_COL_MIN.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>COL_MIN.Parent" xml:space="preserve">
|
||||
<data name=">>H_COL_MIN.Parent" xml:space="preserve">
|
||||
<value>groupBox1</value>
|
||||
</data>
|
||||
<data name=">>COL_MIN.ZOrder" xml:space="preserve">
|
||||
<data name=">>H_COL_MIN.ZOrder" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="COL_MID.Enabled" type="System.Boolean, mscorlib">
|
||||
<data name="H_COL_MID.Enabled" type="System.Boolean, mscorlib">
|
||||
<value>False</value>
|
||||
</data>
|
||||
<data name="COL_MID.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<data name="H_COL_MID.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>17, 117</value>
|
||||
</data>
|
||||
<data name="COL_MID.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="H_COL_MID.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>44, 20</value>
|
||||
</data>
|
||||
<data name="COL_MID.TabIndex" type="System.Int32, mscorlib">
|
||||
<data name="H_COL_MID.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>117</value>
|
||||
</data>
|
||||
<data name="COL_MID.Text" xml:space="preserve">
|
||||
<data name="H_COL_MID.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name=">>COL_MID.Name" xml:space="preserve">
|
||||
<value>COL_MID</value>
|
||||
<data name=">>H_COL_MID.Name" xml:space="preserve">
|
||||
<value>H_COL_MID</value>
|
||||
</data>
|
||||
<data name=">>COL_MID.Type" xml:space="preserve">
|
||||
<data name=">>H_COL_MID.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>COL_MID.Parent" xml:space="preserve">
|
||||
<data name=">>H_COL_MID.Parent" xml:space="preserve">
|
||||
<value>groupBox1</value>
|
||||
</data>
|
||||
<data name=">>COL_MID.ZOrder" xml:space="preserve">
|
||||
<data name=">>H_COL_MID.ZOrder" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="COL_MAX.Enabled" type="System.Boolean, mscorlib">
|
||||
<data name="H_COL_MAX.Enabled" type="System.Boolean, mscorlib">
|
||||
<value>False</value>
|
||||
</data>
|
||||
<data name="COL_MAX.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<data name="H_COL_MAX.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>18, 45</value>
|
||||
</data>
|
||||
<data name="COL_MAX.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="H_COL_MAX.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>43, 20</value>
|
||||
</data>
|
||||
<data name="COL_MAX.TabIndex" type="System.Int32, mscorlib">
|
||||
<data name="H_COL_MAX.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>115</value>
|
||||
</data>
|
||||
<data name="COL_MAX.Text" xml:space="preserve">
|
||||
<data name="H_COL_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name=">>COL_MAX.Name" xml:space="preserve">
|
||||
<value>COL_MAX</value>
|
||||
<data name=">>H_COL_MAX.Name" xml:space="preserve">
|
||||
<value>H_COL_MAX</value>
|
||||
</data>
|
||||
<data name=">>COL_MAX.Type" xml:space="preserve">
|
||||
<data name=">>H_COL_MAX.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>COL_MAX.Parent" xml:space="preserve">
|
||||
<data name=">>H_COL_MAX.Parent" xml:space="preserve">
|
||||
<value>groupBox1</value>
|
||||
</data>
|
||||
<data name=">>COL_MAX.ZOrder" xml:space="preserve">
|
||||
<data name=">>H_COL_MAX.ZOrder" xml:space="preserve">
|
||||
<value>4</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Enabled" type="System.Boolean, mscorlib">
|
||||
@ -556,7 +550,7 @@
|
||||
<value>BUT_0collective</value>
|
||||
</data>
|
||||
<data name=">>BUT_0collective.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BUT_0collective.Parent" xml:space="preserve">
|
||||
<value>groupBox1</value>
|
||||
@ -933,28 +927,28 @@
|
||||
<data name=">>label26.ZOrder" xml:space="preserve">
|
||||
<value>18</value>
|
||||
</data>
|
||||
<data name="PIT_MAX.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<data name="H_PIT_MAX.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>314, 362</value>
|
||||
</data>
|
||||
<data name="PIT_MAX.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="H_PIT_MAX.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>47, 20</value>
|
||||
</data>
|
||||
<data name="PIT_MAX.TabIndex" type="System.Int32, mscorlib">
|
||||
<data name="H_PIT_MAX.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>156</value>
|
||||
</data>
|
||||
<data name="PIT_MAX.Text" xml:space="preserve">
|
||||
<data name="H_PIT_MAX.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name=">>PIT_MAX.Name" xml:space="preserve">
|
||||
<value>PIT_MAX</value>
|
||||
<data name=">>H_PIT_MAX.Name" xml:space="preserve">
|
||||
<value>H_PIT_MAX</value>
|
||||
</data>
|
||||
<data name=">>PIT_MAX.Type" xml:space="preserve">
|
||||
<data name=">>H_PIT_MAX.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>PIT_MAX.Parent" xml:space="preserve">
|
||||
<data name=">>H_PIT_MAX.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>PIT_MAX.ZOrder" xml:space="preserve">
|
||||
<data name=">>H_PIT_MAX.ZOrder" xml:space="preserve">
|
||||
<value>19</value>
|
||||
</data>
|
||||
<data name="label25.AutoSize" type="System.Boolean, mscorlib">
|
||||
@ -987,28 +981,28 @@
|
||||
<data name=">>label25.ZOrder" xml:space="preserve">
|
||||
<value>20</value>
|
||||
</data>
|
||||
<data name="ROL_MAX.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<data name="H_ROL_MAX.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>314, 336</value>
|
||||
</data>
|
||||
<data name="ROL_MAX.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="H_ROL_MAX.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>47, 20</value>
|
||||
</data>
|
||||
<data name="ROL_MAX.TabIndex" type="System.Int32, mscorlib">
|
||||
<data name="H_ROL_MAX.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>154</value>
|
||||
</data>
|
||||
<data name="ROL_MAX.Text" xml:space="preserve">
|
||||
<data name="H_ROL_MAX.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name=">>ROL_MAX.Name" xml:space="preserve">
|
||||
<value>ROL_MAX</value>
|
||||
<data name=">>H_ROL_MAX.Name" xml:space="preserve">
|
||||
<value>H_ROL_MAX</value>
|
||||
</data>
|
||||
<data name=">>ROL_MAX.Type" xml:space="preserve">
|
||||
<data name=">>H_ROL_MAX.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>ROL_MAX.Parent" xml:space="preserve">
|
||||
<data name=">>H_ROL_MAX.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>ROL_MAX.ZOrder" xml:space="preserve">
|
||||
<data name=">>H_ROL_MAX.ZOrder" xml:space="preserve">
|
||||
<value>21</value>
|
||||
</data>
|
||||
<data name="label23.AutoSize" type="System.Boolean, mscorlib">
|
||||
@ -1161,76 +1155,76 @@
|
||||
<data name=">>label18.ZOrder" xml:space="preserve">
|
||||
<value>26</value>
|
||||
</data>
|
||||
<data name="SV3_POS.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<data name="H_SV3_POS.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>57, 314</value>
|
||||
</data>
|
||||
<data name="SV3_POS.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="H_SV3_POS.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>39, 20</value>
|
||||
</data>
|
||||
<data name="SV3_POS.TabIndex" type="System.Int32, mscorlib">
|
||||
<data name="H_SV3_POS.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>146</value>
|
||||
</data>
|
||||
<data name="SV3_POS.Text" xml:space="preserve">
|
||||
<data name="H_SV3_POS.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name=">>SV3_POS.Name" xml:space="preserve">
|
||||
<value>SV3_POS</value>
|
||||
<data name=">>H_SV3_POS.Name" xml:space="preserve">
|
||||
<value>H_SV3_POS</value>
|
||||
</data>
|
||||
<data name=">>SV3_POS.Type" xml:space="preserve">
|
||||
<data name=">>H_SV3_POS.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>SV3_POS.Parent" xml:space="preserve">
|
||||
<data name=">>H_SV3_POS.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>SV3_POS.ZOrder" xml:space="preserve">
|
||||
<data name=">>H_SV3_POS.ZOrder" xml:space="preserve">
|
||||
<value>27</value>
|
||||
</data>
|
||||
<data name="SV2_POS.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<data name="H_SV2_POS.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>57, 288</value>
|
||||
</data>
|
||||
<data name="SV2_POS.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="H_SV2_POS.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>39, 20</value>
|
||||
</data>
|
||||
<data name="SV2_POS.TabIndex" type="System.Int32, mscorlib">
|
||||
<data name="H_SV2_POS.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>145</value>
|
||||
</data>
|
||||
<data name="SV2_POS.Text" xml:space="preserve">
|
||||
<data name="H_SV2_POS.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name=">>SV2_POS.Name" xml:space="preserve">
|
||||
<value>SV2_POS</value>
|
||||
<data name=">>H_SV2_POS.Name" xml:space="preserve">
|
||||
<value>H_SV2_POS</value>
|
||||
</data>
|
||||
<data name=">>SV2_POS.Type" xml:space="preserve">
|
||||
<data name=">>H_SV2_POS.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>SV2_POS.Parent" xml:space="preserve">
|
||||
<data name=">>H_SV2_POS.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>SV2_POS.ZOrder" xml:space="preserve">
|
||||
<data name=">>H_SV2_POS.ZOrder" xml:space="preserve">
|
||||
<value>28</value>
|
||||
</data>
|
||||
<data name="SV1_POS.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<data name="H_SV1_POS.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>57, 262</value>
|
||||
</data>
|
||||
<data name="SV1_POS.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="H_SV1_POS.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>39, 20</value>
|
||||
</data>
|
||||
<data name="SV1_POS.TabIndex" type="System.Int32, mscorlib">
|
||||
<data name="H_SV1_POS.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>144</value>
|
||||
</data>
|
||||
<data name="SV1_POS.Text" xml:space="preserve">
|
||||
<data name="H_SV1_POS.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name=">>SV1_POS.Name" xml:space="preserve">
|
||||
<value>SV1_POS</value>
|
||||
<data name=">>H_SV1_POS.Name" xml:space="preserve">
|
||||
<value>H_SV1_POS</value>
|
||||
</data>
|
||||
<data name=">>SV1_POS.Type" xml:space="preserve">
|
||||
<data name=">>H_SV1_POS.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>SV1_POS.Parent" xml:space="preserve">
|
||||
<data name=">>H_SV1_POS.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>SV1_POS.ZOrder" xml:space="preserve">
|
||||
<data name=">>H_SV1_POS.ZOrder" xml:space="preserve">
|
||||
<value>29</value>
|
||||
</data>
|
||||
<data name="HS3_REV.AutoSize" type="System.Boolean, mscorlib">
|
||||
@ -1360,7 +1354,7 @@
|
||||
<value>HS4</value>
|
||||
</data>
|
||||
<data name=">>HS4.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>HS4.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
@ -1381,7 +1375,7 @@
|
||||
<value>HS3</value>
|
||||
</data>
|
||||
<data name=">>HS3.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>HS3.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
@ -1411,7 +1405,7 @@
|
||||
<value>Gservoloc</value>
|
||||
</data>
|
||||
<data name=">>Gservoloc.Type" xml:space="preserve">
|
||||
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>Gservoloc.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
@ -1576,6 +1570,6 @@
|
||||
<value>ConfigTradHeli</value>
|
||||
</data>
|
||||
<data name=">>$this.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4485.38897, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
</root>
|
@ -38,15 +38,15 @@
|
||||
this.backstageView.Dock = System.Windows.Forms.DockStyle.Fill;
|
||||
this.backstageView.Location = new System.Drawing.Point(0, 0);
|
||||
this.backstageView.Name = "backstageView";
|
||||
this.backstageView.Size = new System.Drawing.Size(823, 468);
|
||||
this.backstageView.Size = new System.Drawing.Size(931, 468);
|
||||
this.backstageView.TabIndex = 0;
|
||||
//
|
||||
// Setup
|
||||
//
|
||||
this.ClientSize = new System.Drawing.Size(823, 468);
|
||||
this.ClientSize = new System.Drawing.Size(931, 468);
|
||||
this.Controls.Add(this.backstageView);
|
||||
this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
|
||||
this.MinimumSize = new System.Drawing.Size(839, 506);
|
||||
this.MinimumSize = new System.Drawing.Size(947, 506);
|
||||
this.Name = "Setup";
|
||||
this.Text = "Setup";
|
||||
this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Setup_FormClosing);
|
||||
|
@ -267,7 +267,7 @@ namespace ArdupilotMega.GCSViews
|
||||
continue;
|
||||
}
|
||||
if (!comPort.BaseStream.IsOpen)
|
||||
lastdata = DateTime.MinValue;
|
||||
lastdata = DateTime.Now;
|
||||
// re-request servo data
|
||||
if (!(lastdata.AddSeconds(8) > DateTime.Now) && comPort.BaseStream.IsOpen)
|
||||
{
|
||||
@ -479,7 +479,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
|
||||
{
|
||||
routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing));
|
||||
routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing, gMapControl1));
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -550,7 +550,7 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
reader.Read();
|
||||
reader.ReadStartElement("CMD");
|
||||
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
|
||||
{
|
||||
reader.ReadToFollowing("APM");
|
||||
}
|
||||
@ -3047,7 +3047,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
|
||||
{
|
||||
routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing) { ToolTipText = MainV2.cs.alt.ToString("0"), ToolTipMode = MarkerTooltipMode.Always });
|
||||
routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing, MainMap) { ToolTipText = MainV2.cs.alt.ToString("0"), ToolTipMode = MarkerTooltipMode.Always });
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -209,8 +209,6 @@ namespace ArdupilotMega
|
||||
sw.Close();
|
||||
TextReader tr = new StreamReader(logfile);
|
||||
|
||||
MainV2.cs.firmware = MainV2.Firmwares.ArduPlane;
|
||||
|
||||
this.Invoke((System.Windows.Forms.MethodInvoker)delegate()
|
||||
{
|
||||
TXT_seriallog.AppendText("Createing KML for " + logfile);
|
||||
@ -373,8 +371,6 @@ namespace ArdupilotMega
|
||||
if (position[positionindex] == null)
|
||||
position[positionindex] = new List<Point3D>();
|
||||
|
||||
MainV2.cs.firmware = MainV2.Firmwares.ArduCopter2;
|
||||
|
||||
double alt = double.Parse(items[5], new System.Globalization.CultureInfo("en-US"));
|
||||
|
||||
position[positionindex].Add(new Point3D(double.Parse(items[4], new System.Globalization.CultureInfo("en-US")), double.Parse(items[3], new System.Globalization.CultureInfo("en-US")), alt));
|
||||
@ -812,8 +808,6 @@ namespace ArdupilotMega
|
||||
|
||||
TextReader tr = new StreamReader(logfile);
|
||||
|
||||
MainV2.cs.firmware = MainV2.Firmwares.ArduPlane;
|
||||
|
||||
while (tr.Peek() != -1)
|
||||
{
|
||||
processLine(tr.ReadLine());
|
||||
@ -887,8 +881,6 @@ namespace ArdupilotMega
|
||||
{
|
||||
TextReader tr = new StreamReader(logfile);
|
||||
|
||||
MainV2.cs.firmware = MainV2.Firmwares.ArduPlane;
|
||||
|
||||
while (tr.Peek() != -1)
|
||||
{
|
||||
processLine(tr.ReadLine());
|
||||
|
@ -157,7 +157,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
reader.Read();
|
||||
reader.ReadStartElement("LOGFORMAT");
|
||||
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
|
||||
{
|
||||
reader.ReadToFollowing("APM");
|
||||
}
|
||||
|
@ -1027,8 +1027,9 @@ namespace ArdupilotMega
|
||||
|
||||
public void requestDatastream(byte id, byte hzrate)
|
||||
{
|
||||
|
||||
double pps = 0;
|
||||
|
||||
/*
|
||||
switch (id)
|
||||
{
|
||||
case (byte)MAVLink.MAV_DATA_STREAM.ALL:
|
||||
@ -1117,8 +1118,9 @@ namespace ArdupilotMega
|
||||
{
|
||||
return;
|
||||
}
|
||||
*/
|
||||
|
||||
log.InfoFormat("Request stream {0} at {1} hz : currently {2}", Enum.Parse(typeof(MAV_DATA_STREAM), id.ToString()), hzrate, pps);
|
||||
log.InfoFormat("Request stream {0} at {1} hz", Enum.Parse(typeof(MAV_DATA_STREAM), id.ToString()), hzrate);
|
||||
getDatastream(id, hzrate);
|
||||
}
|
||||
|
||||
|
169
Tools/ArdupilotMegaPlanner/MainV2.Designer.cs
generated
169
Tools/ArdupilotMegaPlanner/MainV2.Designer.cs
generated
@ -29,23 +29,56 @@
|
||||
private void InitializeComponent()
|
||||
{
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2));
|
||||
this.MyView = new System.Windows.Forms.Panel();
|
||||
this.MainMenu = new System.Windows.Forms.MenuStrip();
|
||||
this.MenuFlightData = new System.Windows.Forms.ToolStripButton();
|
||||
this.MenuFlightPlanner = new System.Windows.Forms.ToolStripButton();
|
||||
this.MenuConfiguration = new System.Windows.Forms.ToolStripButton();
|
||||
this.MenuSimulation = new System.Windows.Forms.ToolStripButton();
|
||||
this.MenuFirmware = new System.Windows.Forms.ToolStripButton();
|
||||
this.MenuConnect = new System.Windows.Forms.ToolStripButton();
|
||||
this.CMB_serialport = new System.Windows.Forms.ToolStripComboBox();
|
||||
this.MainMenu = new System.Windows.Forms.MenuStrip();
|
||||
this.MenuTerminal = new System.Windows.Forms.ToolStripButton();
|
||||
this.CMB_baudrate = new System.Windows.Forms.ToolStripComboBox();
|
||||
this.TOOL_APMFirmware = new System.Windows.Forms.ToolStripComboBox();
|
||||
this.MenuHelp = new System.Windows.Forms.ToolStripButton();
|
||||
this.toolStripMenuItem1 = new System.Windows.Forms.ToolStripMenuItem();
|
||||
this.MyView = new System.Windows.Forms.Panel();
|
||||
this.MenuConnect = new System.Windows.Forms.ToolStripButton();
|
||||
this.toolStripConnectionControl = new ArdupilotMega.Controls.ToolStripConnectionControl();
|
||||
this.MainMenu.SuspendLayout();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// MyView
|
||||
//
|
||||
this.MyView.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(38)))), ((int)(((byte)(39)))), ((int)(((byte)(40)))));
|
||||
this.MyView.Dock = System.Windows.Forms.DockStyle.Fill;
|
||||
this.MyView.ForeColor = System.Drawing.Color.White;
|
||||
this.MyView.Location = new System.Drawing.Point(0, 76);
|
||||
this.MyView.Margin = new System.Windows.Forms.Padding(0);
|
||||
this.MyView.Name = "MyView";
|
||||
this.MyView.Size = new System.Drawing.Size(1008, 461);
|
||||
this.MyView.TabIndex = 3;
|
||||
//
|
||||
// MainMenu
|
||||
//
|
||||
this.MainMenu.BackColor = System.Drawing.SystemColors.Control;
|
||||
this.MainMenu.BackgroundImage = ((System.Drawing.Image)(resources.GetObject("MainMenu.BackgroundImage")));
|
||||
this.MainMenu.GripMargin = new System.Windows.Forms.Padding(0);
|
||||
this.MainMenu.ImageScalingSize = new System.Drawing.Size(76, 76);
|
||||
this.MainMenu.Items.AddRange(new System.Windows.Forms.ToolStripItem[] {
|
||||
this.MenuFlightData,
|
||||
this.MenuFlightPlanner,
|
||||
this.MenuConfiguration,
|
||||
this.MenuSimulation,
|
||||
this.MenuFirmware,
|
||||
this.MenuTerminal,
|
||||
this.MenuHelp,
|
||||
this.MenuConnect,
|
||||
this.toolStripConnectionControl});
|
||||
this.MainMenu.LayoutStyle = System.Windows.Forms.ToolStripLayoutStyle.HorizontalStackWithOverflow;
|
||||
this.MainMenu.Location = new System.Drawing.Point(0, 0);
|
||||
this.MainMenu.Name = "MainMenu";
|
||||
this.MainMenu.Padding = new System.Windows.Forms.Padding(0);
|
||||
this.MainMenu.RenderMode = System.Windows.Forms.ToolStripRenderMode.Professional;
|
||||
this.MainMenu.Size = new System.Drawing.Size(1008, 76);
|
||||
this.MainMenu.TabIndex = 5;
|
||||
this.MainMenu.Text = "menuStrip1";
|
||||
//
|
||||
// MenuFlightData
|
||||
//
|
||||
this.MenuFlightData.AutoSize = false;
|
||||
@ -114,57 +147,6 @@
|
||||
this.MenuFirmware.ToolTipText = "Firmware";
|
||||
this.MenuFirmware.Click += new System.EventHandler(this.MenuFirmware_Click);
|
||||
//
|
||||
// MenuConnect
|
||||
//
|
||||
this.MenuConnect.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
|
||||
this.MenuConnect.AutoSize = false;
|
||||
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
|
||||
this.MenuConnect.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
|
||||
this.MenuConnect.ImageTransparentColor = System.Drawing.Color.Magenta;
|
||||
this.MenuConnect.Margin = new System.Windows.Forms.Padding(0);
|
||||
this.MenuConnect.Name = "MenuConnect";
|
||||
this.MenuConnect.Padding = new System.Windows.Forms.Padding(0, 0, 72, 72);
|
||||
this.MenuConnect.Size = new System.Drawing.Size(76, 76);
|
||||
this.MenuConnect.Click += new System.EventHandler(this.MenuConnect_Click);
|
||||
//
|
||||
// CMB_serialport
|
||||
//
|
||||
this.CMB_serialport.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
|
||||
this.CMB_serialport.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
|
||||
this.CMB_serialport.Name = "CMB_serialport";
|
||||
this.CMB_serialport.Size = new System.Drawing.Size(150, 76);
|
||||
this.CMB_serialport.SelectedIndexChanged += new System.EventHandler(this.CMB_serialport_SelectedIndexChanged);
|
||||
this.CMB_serialport.Enter += new System.EventHandler(this.CMB_serialport_Enter);
|
||||
this.CMB_serialport.Click += new System.EventHandler(this.CMB_serialport_Click);
|
||||
//
|
||||
// MainMenu
|
||||
//
|
||||
this.MainMenu.AutoSize = false;
|
||||
this.MainMenu.BackColor = System.Drawing.SystemColors.Control;
|
||||
this.MainMenu.BackgroundImage = ((System.Drawing.Image)(resources.GetObject("MainMenu.BackgroundImage")));
|
||||
this.MainMenu.GripMargin = new System.Windows.Forms.Padding(0);
|
||||
this.MainMenu.ImageScalingSize = new System.Drawing.Size(76, 76);
|
||||
this.MainMenu.Items.AddRange(new System.Windows.Forms.ToolStripItem[] {
|
||||
this.MenuFlightData,
|
||||
this.MenuFlightPlanner,
|
||||
this.MenuConfiguration,
|
||||
this.MenuSimulation,
|
||||
this.MenuFirmware,
|
||||
this.MenuTerminal,
|
||||
this.MenuConnect,
|
||||
this.CMB_baudrate,
|
||||
this.CMB_serialport,
|
||||
this.TOOL_APMFirmware,
|
||||
this.MenuHelp});
|
||||
this.MainMenu.LayoutStyle = System.Windows.Forms.ToolStripLayoutStyle.HorizontalStackWithOverflow;
|
||||
this.MainMenu.Location = new System.Drawing.Point(0, 0);
|
||||
this.MainMenu.Name = "MainMenu";
|
||||
this.MainMenu.Padding = new System.Windows.Forms.Padding(0);
|
||||
this.MainMenu.RenderMode = System.Windows.Forms.ToolStripRenderMode.Professional;
|
||||
this.MainMenu.Size = new System.Drawing.Size(1008, 76);
|
||||
this.MainMenu.TabIndex = 1;
|
||||
this.MainMenu.Text = "menuStrip1";
|
||||
//
|
||||
// MenuTerminal
|
||||
//
|
||||
this.MenuTerminal.AutoSize = false;
|
||||
@ -179,32 +161,6 @@
|
||||
this.MenuTerminal.ToolTipText = "Terminal";
|
||||
this.MenuTerminal.Click += new System.EventHandler(this.MenuTerminal_Click);
|
||||
//
|
||||
// CMB_baudrate
|
||||
//
|
||||
this.CMB_baudrate.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
|
||||
this.CMB_baudrate.Items.AddRange(new object[] {
|
||||
"4800",
|
||||
"9600",
|
||||
"14400",
|
||||
"19200",
|
||||
"28800",
|
||||
"38400",
|
||||
"57600",
|
||||
"115200"});
|
||||
this.CMB_baudrate.Name = "CMB_baudrate";
|
||||
this.CMB_baudrate.Size = new System.Drawing.Size(76, 76);
|
||||
this.CMB_baudrate.SelectedIndexChanged += new System.EventHandler(this.CMB_baudrate_SelectedIndexChanged);
|
||||
this.CMB_baudrate.TextChanged += new System.EventHandler(this.CMB_baudrate_TextChanged);
|
||||
//
|
||||
// TOOL_APMFirmware
|
||||
//
|
||||
this.TOOL_APMFirmware.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
|
||||
this.TOOL_APMFirmware.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
|
||||
this.TOOL_APMFirmware.MaxDropDownItems = 2;
|
||||
this.TOOL_APMFirmware.Name = "TOOL_APMFirmware";
|
||||
this.TOOL_APMFirmware.Size = new System.Drawing.Size(121, 76);
|
||||
this.TOOL_APMFirmware.SelectedIndexChanged += new System.EventHandler(this.TOOL_APMFirmware_SelectedIndexChanged);
|
||||
//
|
||||
// MenuHelp
|
||||
//
|
||||
this.MenuHelp.AutoSize = false;
|
||||
@ -219,22 +175,25 @@
|
||||
this.MenuHelp.ToolTipText = "Terminal";
|
||||
this.MenuHelp.Click += new System.EventHandler(this.MenuHelp_Click);
|
||||
//
|
||||
// toolStripMenuItem1
|
||||
// MenuConnect
|
||||
//
|
||||
this.toolStripMenuItem1.Name = "toolStripMenuItem1";
|
||||
this.toolStripMenuItem1.Size = new System.Drawing.Size(141, 20);
|
||||
this.toolStripMenuItem1.Text = "toolStripMenuItem1";
|
||||
this.MenuConnect.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
|
||||
this.MenuConnect.AutoSize = false;
|
||||
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
|
||||
this.MenuConnect.DisplayStyle = System.Windows.Forms.ToolStripItemDisplayStyle.Image;
|
||||
this.MenuConnect.ImageTransparentColor = System.Drawing.Color.Magenta;
|
||||
this.MenuConnect.Margin = new System.Windows.Forms.Padding(0);
|
||||
this.MenuConnect.Name = "MenuConnect";
|
||||
this.MenuConnect.Padding = new System.Windows.Forms.Padding(0, 0, 72, 72);
|
||||
this.MenuConnect.Size = new System.Drawing.Size(76, 76);
|
||||
this.MenuConnect.Click += new System.EventHandler(this.MenuConnect_Click);
|
||||
//
|
||||
// MyView
|
||||
// toolStripConnectionControl
|
||||
//
|
||||
this.MyView.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(38)))), ((int)(((byte)(39)))), ((int)(((byte)(40)))));
|
||||
this.MyView.Dock = System.Windows.Forms.DockStyle.Fill;
|
||||
this.MyView.ForeColor = System.Drawing.Color.White;
|
||||
this.MyView.Location = new System.Drawing.Point(0, 76);
|
||||
this.MyView.Margin = new System.Windows.Forms.Padding(0);
|
||||
this.MyView.Name = "MyView";
|
||||
this.MyView.Size = new System.Drawing.Size(1008, 461);
|
||||
this.MyView.TabIndex = 3;
|
||||
this.toolStripConnectionControl.Alignment = System.Windows.Forms.ToolStripItemAlignment.Right;
|
||||
this.toolStripConnectionControl.BackColor = System.Drawing.Color.Transparent;
|
||||
this.toolStripConnectionControl.Name = "toolStripConnectionControl";
|
||||
this.toolStripConnectionControl.Size = new System.Drawing.Size(203, 73);
|
||||
//
|
||||
// MainV2
|
||||
//
|
||||
@ -257,26 +216,24 @@
|
||||
this.MainMenu.ResumeLayout(false);
|
||||
this.MainMenu.PerformLayout();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
|
||||
private System.Windows.Forms.Panel MyView;
|
||||
private System.Windows.Forms.MenuStrip MainMenu;
|
||||
private System.Windows.Forms.ToolStripButton MenuFlightData;
|
||||
private System.Windows.Forms.ToolStripButton MenuFlightPlanner;
|
||||
private System.Windows.Forms.ToolStripButton MenuConfiguration;
|
||||
private System.Windows.Forms.ToolStripButton MenuSimulation;
|
||||
private System.Windows.Forms.ToolStripButton MenuFirmware;
|
||||
private System.Windows.Forms.ToolStripComboBox CMB_serialport;
|
||||
private System.Windows.Forms.ToolStripButton MenuConnect;
|
||||
private System.Windows.Forms.MenuStrip MainMenu;
|
||||
private System.Windows.Forms.ToolStripMenuItem toolStripMenuItem1;
|
||||
private System.Windows.Forms.ToolStripComboBox CMB_baudrate;
|
||||
private System.Windows.Forms.Panel MyView;
|
||||
private System.Windows.Forms.ToolStripButton MenuTerminal;
|
||||
private System.Windows.Forms.ToolStripComboBox TOOL_APMFirmware;
|
||||
private System.Windows.Forms.ToolStripButton MenuConnect;
|
||||
|
||||
private System.Windows.Forms.ToolStripButton MenuHelp;
|
||||
//public static WebCam_Capture.WebCamCapture webCamCapture1;
|
||||
|
||||
private ArdupilotMega.Controls.ToolStripConnectionControl toolStripConnectionControl;
|
||||
}
|
||||
}
|
@ -31,6 +31,8 @@ namespace ArdupilotMega
|
||||
{
|
||||
private static readonly ILog log =
|
||||
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
|
||||
|
||||
// used to hide/show console window
|
||||
[DllImport("user32.dll")]
|
||||
public static extern int FindWindow(string szClass, string szTitle);
|
||||
[DllImport("user32.dll")]
|
||||
@ -39,41 +41,88 @@ namespace ArdupilotMega
|
||||
const int SW_SHOWNORMAL = 1;
|
||||
const int SW_HIDE = 0;
|
||||
|
||||
/// <summary>
|
||||
/// Main Comport interface
|
||||
/// </summary>
|
||||
public static MAVLink comPort = new MAVLink();
|
||||
/// <summary>
|
||||
/// Comport name
|
||||
/// </summary>
|
||||
public static string comPortName = "";
|
||||
/// <summary>
|
||||
/// use to store all internal config
|
||||
/// </summary>
|
||||
public static Hashtable config = new Hashtable();
|
||||
/// <summary>
|
||||
/// used to prevent comport access for exclusive use
|
||||
/// </summary>
|
||||
public static bool giveComport = false;
|
||||
public static Firmwares APMFirmware = Firmwares.ArduPlane;
|
||||
/// <summary>
|
||||
/// mono detection
|
||||
/// </summary>
|
||||
public static bool MONO = false;
|
||||
|
||||
/// <summary>
|
||||
/// speech engein enable
|
||||
/// </summary>
|
||||
public static bool speechEnable = false;
|
||||
/// <summary>
|
||||
/// spech engine static class
|
||||
/// </summary>
|
||||
public static Speech speechEngine = null;
|
||||
|
||||
/// <summary>
|
||||
/// joystick static class
|
||||
/// </summary>
|
||||
public static Joystick joystick = null;
|
||||
/// <summary>
|
||||
/// track last joystick packet sent. used to track timming
|
||||
/// </summary>
|
||||
DateTime lastjoystick = DateTime.Now;
|
||||
|
||||
/// <summary>
|
||||
/// hud background image grabber from a video stream - not realy that efficent. ie no hardware overlays etc.
|
||||
/// </summary>
|
||||
public static WebCamService.Capture cam = null;
|
||||
|
||||
/// <summary>
|
||||
/// the static global state of the currently connected MAV
|
||||
/// </summary>
|
||||
public static CurrentState cs = new CurrentState();
|
||||
|
||||
/// <summary>
|
||||
/// controls the main serial reader thread
|
||||
/// </summary>
|
||||
bool serialThread = false;
|
||||
|
||||
/// <summary>
|
||||
/// unused at this point - potential to move all forms to this single binding source. need to evalutate performance/exception issues
|
||||
/// </summary>
|
||||
static internal BindingSource bs;
|
||||
|
||||
TcpListener listener;
|
||||
|
||||
DateTime heatbeatSend = DateTime.Now;
|
||||
|
||||
/// <summary>
|
||||
/// used for mini https server for websockets/mjpeg video stream, and network link kmls
|
||||
/// </summary>
|
||||
private TcpListener listener;
|
||||
/// <summary>
|
||||
/// track the last heartbeat sent
|
||||
/// </summary>
|
||||
private DateTime heatbeatSend = DateTime.Now;
|
||||
/// <summary>
|
||||
/// used to call anything as needed.
|
||||
/// </summary>
|
||||
public static MainV2 instance = null;
|
||||
|
||||
/// <summary>
|
||||
/// used to feed in a network link kml to the http server
|
||||
/// </summary>
|
||||
public string georefkml = "";
|
||||
|
||||
/// <summary>
|
||||
/// enum of firmwares
|
||||
/// </summary>
|
||||
public enum Firmwares
|
||||
{
|
||||
ArduPlane,
|
||||
ArduCopter2,
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// declared here if i want a "single" instance of the form
|
||||
/// ie configuration gets reloaded on every click
|
||||
/// </summary>
|
||||
GCSViews.FlightData FlightData;
|
||||
GCSViews.FlightPlanner FlightPlanner;
|
||||
GCSViews.Configuration Configuration;
|
||||
@ -82,13 +131,20 @@ namespace ArdupilotMega
|
||||
GCSViews.Firmware Firmware;
|
||||
GCSViews.Terminal Terminal;
|
||||
|
||||
/// <summary>
|
||||
/// control for the serial port and firmware selector.
|
||||
/// </summary>
|
||||
private ConnectionControl _connectionControl;
|
||||
|
||||
public MainV2()
|
||||
{
|
||||
Form splash = new Splash();
|
||||
splash.Show();
|
||||
|
||||
string strVersion = System.Reflection.Assembly.GetExecutingAssembly().GetName().Version.ToString();
|
||||
strVersion = "";
|
||||
|
||||
strVersion = "mav " + MAVLink.MAVLINK_WIRE_PROTOCOL_VERSION;
|
||||
|
||||
splash.Text = "APM Planner " + Application.ProductVersion + " " + strVersion + " By Michael Oborne";
|
||||
|
||||
splash.Refresh();
|
||||
@ -98,6 +154,14 @@ namespace ArdupilotMega
|
||||
instance = this;
|
||||
|
||||
InitializeComponent();
|
||||
|
||||
_connectionControl = toolStripConnectionControl.ConnectionControl;
|
||||
_connectionControl.CMB_baudrate.TextChanged += this.CMB_baudrate_TextChanged;
|
||||
_connectionControl.CMB_baudrate.SelectedIndexChanged += this.CMB_baudrate_SelectedIndexChanged;
|
||||
_connectionControl.CMB_serialport.SelectedIndexChanged += this.CMB_serialport_SelectedIndexChanged;
|
||||
_connectionControl.CMB_serialport.Enter += this.CMB_serialport_Enter;
|
||||
_connectionControl.CMB_serialport.Click += this.CMB_serialport_Click;
|
||||
_connectionControl.TOOL_APMFirmware.SelectedIndexChanged += this.TOOL_APMFirmware_SelectedIndexChanged;
|
||||
|
||||
srtm.datadirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "srtm";
|
||||
|
||||
@ -113,24 +177,35 @@ namespace ArdupilotMega
|
||||
List<object> list = new List<object>();
|
||||
foreach (object obj in Enum.GetValues(typeof(Firmwares)))
|
||||
{
|
||||
TOOL_APMFirmware.Items.Add(obj);
|
||||
_connectionControl.TOOL_APMFirmware.Items.Add(obj);
|
||||
}
|
||||
|
||||
if (TOOL_APMFirmware.Items.Count > 0)
|
||||
TOOL_APMFirmware.SelectedIndex = 0;
|
||||
if (_connectionControl.TOOL_APMFirmware.Items.Count > 0)
|
||||
_connectionControl.TOOL_APMFirmware.SelectedIndex = 0;
|
||||
|
||||
this.Text = splash.Text;
|
||||
|
||||
comPort.BaseStream.BaudRate = 115200;
|
||||
|
||||
CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
|
||||
CMB_serialport.Items.Add("TCP");
|
||||
CMB_serialport.Items.Add("UDP");
|
||||
if (CMB_serialport.Items.Count > 0)
|
||||
// ** Old
|
||||
// CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
|
||||
// CMB_serialport.Items.Add("TCP");
|
||||
// CMB_serialport.Items.Add("UDP");
|
||||
// if (CMB_serialport.Items.Count > 0)
|
||||
// {
|
||||
// CMB_baudrate.SelectedIndex = 7;
|
||||
// CMB_serialport.SelectedIndex = 0;
|
||||
// }
|
||||
// ** new
|
||||
_connectionControl.CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
|
||||
_connectionControl.CMB_serialport.Items.Add("TCP");
|
||||
_connectionControl.CMB_serialport.Items.Add("UDP");
|
||||
if (_connectionControl.CMB_serialport.Items.Count > 0)
|
||||
{
|
||||
CMB_baudrate.SelectedIndex = 7;
|
||||
CMB_serialport.SelectedIndex = 0;
|
||||
_connectionControl.CMB_baudrate.SelectedIndex = 7;
|
||||
_connectionControl.CMB_serialport.SelectedIndex = 0;
|
||||
}
|
||||
// ** Done
|
||||
|
||||
splash.Refresh();
|
||||
Application.DoEvents();
|
||||
@ -172,7 +247,7 @@ namespace ArdupilotMega
|
||||
if (MainV2.config["CHK_GDIPlus"] != null)
|
||||
GCSViews.FlightData.myhud.UseOpenGL = !bool.Parse(MainV2.config["CHK_GDIPlus"].ToString());
|
||||
|
||||
changeunits();
|
||||
ChangeUnits();
|
||||
|
||||
try
|
||||
{
|
||||
@ -258,6 +333,9 @@ namespace ArdupilotMega
|
||||
splash.Close();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// used to create planner screenshots - access by control-s
|
||||
/// </summary>
|
||||
internal void ScreenShot()
|
||||
{
|
||||
Rectangle bounds = Screen.GetBounds(Point.Empty);
|
||||
@ -276,13 +354,13 @@ namespace ArdupilotMega
|
||||
|
||||
private void CMB_serialport_Click(object sender, EventArgs e)
|
||||
{
|
||||
string oldport = CMB_serialport.Text;
|
||||
CMB_serialport.Items.Clear();
|
||||
CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
|
||||
CMB_serialport.Items.Add("TCP");
|
||||
CMB_serialport.Items.Add("UDP");
|
||||
if (CMB_serialport.Items.Contains(oldport))
|
||||
CMB_serialport.Text = oldport;
|
||||
string oldport = _connectionControl.CMB_serialport.Text;
|
||||
_connectionControl.CMB_serialport.Items.Clear();
|
||||
_connectionControl.CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
|
||||
_connectionControl.CMB_serialport.Items.Add("TCP");
|
||||
_connectionControl.CMB_serialport.Items.Add("UDP");
|
||||
if (_connectionControl.CMB_serialport.Items.Contains(oldport))
|
||||
_connectionControl.CMB_serialport.Text = oldport;
|
||||
}
|
||||
|
||||
|
||||
@ -474,11 +552,11 @@ namespace ArdupilotMega
|
||||
}
|
||||
else
|
||||
{
|
||||
if (CMB_serialport.Text == "TCP")
|
||||
if (_connectionControl.CMB_serialport.Text == "TCP")
|
||||
{
|
||||
comPort.BaseStream = new TcpSerial();
|
||||
}
|
||||
else if (CMB_serialport.Text == "UDP")
|
||||
else if (_connectionControl.CMB_serialport.Text == "UDP")
|
||||
{
|
||||
comPort.BaseStream = new UdpSerial();
|
||||
}
|
||||
@ -490,31 +568,32 @@ namespace ArdupilotMega
|
||||
try
|
||||
{
|
||||
// set port, then options
|
||||
comPort.BaseStream.PortName = CMB_serialport.Text;
|
||||
comPort.BaseStream.PortName = _connectionControl.CMB_serialport.Text;
|
||||
|
||||
comPort.BaseStream.DataBits = 8;
|
||||
comPort.BaseStream.StopBits = (StopBits)Enum.Parse(typeof(StopBits), "1");
|
||||
comPort.BaseStream.Parity = (Parity)Enum.Parse(typeof(Parity), "None");
|
||||
try
|
||||
{
|
||||
comPort.BaseStream.BaudRate = int.Parse(CMB_baudrate.Text);
|
||||
comPort.BaseStream.BaudRate = int.Parse(_connectionControl.CMB_baudrate.Text);
|
||||
}
|
||||
catch { }
|
||||
|
||||
if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true)
|
||||
comPort.BaseStream.toggleDTR();
|
||||
|
||||
// false here
|
||||
comPort.BaseStream.DtrEnable = false;
|
||||
comPort.BaseStream.RtsEnable = false;
|
||||
|
||||
if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true)
|
||||
comPort.BaseStream.toggleDTR();
|
||||
|
||||
// if reset on connect is on dtr will be true here
|
||||
|
||||
// cleanup from any previous sessions
|
||||
if (comPort.logfile != null)
|
||||
comPort.logfile.Close();
|
||||
|
||||
if (comPort.rawlogfile != null)
|
||||
comPort.rawlogfile.Close();
|
||||
|
||||
// setup to record new logs
|
||||
try
|
||||
{
|
||||
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
|
||||
@ -524,39 +603,44 @@ namespace ArdupilotMega
|
||||
}
|
||||
catch { CustomMessageBox.Show("Failed to create log - wont log this session"); } // soft fail
|
||||
|
||||
// do the connect
|
||||
comPort.Open(true);
|
||||
|
||||
// detect firmware we are conected to.
|
||||
if (comPort.param["SYSID_SW_TYPE"] != null)
|
||||
{
|
||||
if (float.Parse(comPort.param["SYSID_SW_TYPE"].ToString()) == 10)
|
||||
{
|
||||
TOOL_APMFirmware.SelectedIndex = TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduCopter2);
|
||||
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduCopter2);
|
||||
}
|
||||
else if (float.Parse(comPort.param["SYSID_SW_TYPE"].ToString()) == 0)
|
||||
{
|
||||
TOOL_APMFirmware.SelectedIndex = TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduPlane);
|
||||
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduPlane);
|
||||
}
|
||||
}
|
||||
|
||||
cs.firmware = APMFirmware;
|
||||
|
||||
config[CMB_serialport.Text + "_BAUD"] = CMB_baudrate.Text;
|
||||
// save the baudrate for this port
|
||||
config[_connectionControl.CMB_serialport.Text + "_BAUD"] = _connectionControl.CMB_baudrate.Text;
|
||||
|
||||
// load wps on connect option.
|
||||
if (config["loadwpsonconnect"] != null && bool.Parse(config["loadwpsonconnect"].ToString()) == true)
|
||||
{
|
||||
MenuFlightPlanner_Click(null, null);
|
||||
FlightPlanner.BUT_read_Click(null, null);
|
||||
}
|
||||
|
||||
// set connected icon
|
||||
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.disconnect;
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Warn(ex.ToString());
|
||||
try
|
||||
{
|
||||
comPort.Close();
|
||||
}
|
||||
catch { }
|
||||
// detect firmware -> scan eeprom contents -> error if no valid ap param/apvar header detected.
|
||||
try
|
||||
{
|
||||
string version = ArduinoDetect.DetectVersion(comPort.BaseStream.PortName);
|
||||
@ -601,10 +685,10 @@ namespace ArdupilotMega
|
||||
|
||||
private void CMB_serialport_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
comPortName = CMB_serialport.Text;
|
||||
comPortName = _connectionControl.CMB_serialport.Text;
|
||||
if (comPortName == "UDP" || comPortName == "TCP")
|
||||
{
|
||||
CMB_baudrate.Enabled = false;
|
||||
_connectionControl.CMB_baudrate.Enabled = false;
|
||||
if (comPortName == "TCP")
|
||||
MainV2.comPort.BaseStream = new TcpSerial();
|
||||
if (comPortName == "UDP")
|
||||
@ -612,35 +696,32 @@ namespace ArdupilotMega
|
||||
}
|
||||
else
|
||||
{
|
||||
CMB_baudrate.Enabled = true;
|
||||
_connectionControl.CMB_baudrate.Enabled = true;
|
||||
MainV2.comPort.BaseStream = new ArdupilotMega.SerialPort();
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
comPort.BaseStream.PortName = CMB_serialport.Text;
|
||||
comPort.BaseStream.PortName = _connectionControl.CMB_serialport.Text;
|
||||
|
||||
MainV2.comPort.BaseStream.BaudRate = int.Parse(CMB_baudrate.Text);
|
||||
MainV2.comPort.BaseStream.BaudRate = int.Parse(_connectionControl.CMB_baudrate.Text);
|
||||
|
||||
if (config[CMB_serialport.Text + "_BAUD"] != null)
|
||||
// check for saved baud rate and restore
|
||||
if (config[_connectionControl.CMB_serialport.Text + "_BAUD"] != null)
|
||||
{
|
||||
CMB_baudrate.Text = config[CMB_serialport.Text + "_BAUD"].ToString();
|
||||
_connectionControl.CMB_baudrate.Text = config[_connectionControl.CMB_serialport.Text + "_BAUD"].ToString();
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
private void toolStripMenuItem2_Click(object sender, EventArgs e)
|
||||
{
|
||||
//Form temp = new Main();
|
||||
//temp.Show();
|
||||
}
|
||||
|
||||
private void MainV2_FormClosed(object sender, FormClosedEventArgs e)
|
||||
{
|
||||
// shutdown threads
|
||||
GCSViews.FlightData.threadrun = 0;
|
||||
GCSViews.Simulation.threadrun = 0;
|
||||
|
||||
// shutdown local thread
|
||||
serialThread = false;
|
||||
|
||||
try
|
||||
@ -665,6 +746,8 @@ namespace ArdupilotMega
|
||||
}
|
||||
catch { }
|
||||
|
||||
|
||||
// save config
|
||||
xmlconfig(true);
|
||||
}
|
||||
|
||||
@ -675,8 +758,6 @@ namespace ArdupilotMega
|
||||
{
|
||||
try
|
||||
{
|
||||
//System.Configuration.Configuration appconfig = System.Configuration.ConfigurationManager.OpenExeConfiguration(System.Configuration.ConfigurationUserLevel.None);
|
||||
|
||||
XmlTextWriter xmlwriter = new XmlTextWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"config.xml", Encoding.ASCII);
|
||||
xmlwriter.Formatting = Formatting.Indented;
|
||||
|
||||
@ -686,13 +767,9 @@ namespace ArdupilotMega
|
||||
|
||||
xmlwriter.WriteElementString("comport", comPortName);
|
||||
|
||||
xmlwriter.WriteElementString("baudrate", CMB_baudrate.Text);
|
||||
xmlwriter.WriteElementString("baudrate", _connectionControl.CMB_baudrate.Text);
|
||||
|
||||
xmlwriter.WriteElementString("APMFirmware", APMFirmware.ToString());
|
||||
|
||||
//appconfig.AppSettings.Settings.Add("comport", comportname);
|
||||
//appconfig.AppSettings.Settings.Add("baudrate", CMB_baudrate.Text);
|
||||
//appconfig.AppSettings.Settings.Add("APMFirmware", APMFirmware.ToString());
|
||||
xmlwriter.WriteElementString("APMFirmware", MainV2.cs.firmware.ToString());
|
||||
|
||||
foreach (string key in config.Keys)
|
||||
{
|
||||
@ -701,8 +778,6 @@ namespace ArdupilotMega
|
||||
if (key == "" || key.Contains("/")) // "/dev/blah"
|
||||
continue;
|
||||
xmlwriter.WriteElementString(key, config[key].ToString());
|
||||
|
||||
//appconfig.AppSettings.Settings.Add(key, config[key].ToString());
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
@ -711,8 +786,6 @@ namespace ArdupilotMega
|
||||
|
||||
xmlwriter.WriteEndDocument();
|
||||
xmlwriter.Close();
|
||||
|
||||
//appconfig.Save();
|
||||
}
|
||||
catch (Exception ex) { CustomMessageBox.Show(ex.ToString()); }
|
||||
}
|
||||
@ -732,10 +805,10 @@ namespace ArdupilotMega
|
||||
case "comport":
|
||||
string temp = xmlreader.ReadString();
|
||||
|
||||
CMB_serialport.SelectedIndex = CMB_serialport.FindString(temp);
|
||||
if (CMB_serialport.SelectedIndex == -1)
|
||||
_connectionControl.CMB_serialport.SelectedIndex = _connectionControl.CMB_serialport.FindString(temp);
|
||||
if (_connectionControl.CMB_serialport.SelectedIndex == -1)
|
||||
{
|
||||
CMB_serialport.Text = temp; // allows ports that dont exist - yet
|
||||
_connectionControl.CMB_serialport.Text = temp; // allows ports that dont exist - yet
|
||||
}
|
||||
comPort.BaseStream.PortName = temp;
|
||||
comPortName = temp;
|
||||
@ -743,20 +816,20 @@ namespace ArdupilotMega
|
||||
case "baudrate":
|
||||
string temp2 = xmlreader.ReadString();
|
||||
|
||||
CMB_baudrate.SelectedIndex = CMB_baudrate.FindString(temp2);
|
||||
if (CMB_baudrate.SelectedIndex == -1)
|
||||
_connectionControl.CMB_baudrate.SelectedIndex = _connectionControl.CMB_baudrate.FindString(temp2);
|
||||
if (_connectionControl.CMB_baudrate.SelectedIndex == -1)
|
||||
{
|
||||
CMB_baudrate.Text = temp2;
|
||||
_connectionControl.CMB_baudrate.Text = temp2;
|
||||
//CMB_baudrate.SelectedIndex = CMB_baudrate.FindString("57600"); ; // must exist
|
||||
}
|
||||
//bau = int.Parse(CMB_baudrate.Text);
|
||||
break;
|
||||
case "APMFirmware":
|
||||
string temp3 = xmlreader.ReadString();
|
||||
TOOL_APMFirmware.SelectedIndex = TOOL_APMFirmware.FindStringExact(temp3);
|
||||
if (TOOL_APMFirmware.SelectedIndex == -1)
|
||||
TOOL_APMFirmware.SelectedIndex = 0;
|
||||
APMFirmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), TOOL_APMFirmware.Text);
|
||||
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.FindStringExact(temp3);
|
||||
if (_connectionControl.TOOL_APMFirmware.SelectedIndex == -1)
|
||||
_connectionControl.TOOL_APMFirmware.SelectedIndex = 0;
|
||||
MainV2.cs.firmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), _connectionControl.TOOL_APMFirmware.Text);
|
||||
break;
|
||||
case "Config":
|
||||
break;
|
||||
@ -781,11 +854,16 @@ namespace ArdupilotMega
|
||||
{
|
||||
try
|
||||
{
|
||||
comPort.BaseStream.BaudRate = int.Parse(CMB_baudrate.Text);
|
||||
comPort.BaseStream.BaudRate = int.Parse(_connectionControl.CMB_baudrate.Text);
|
||||
}
|
||||
catch
|
||||
{
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// thread used to send joystick packets to the MAV
|
||||
/// </summary>
|
||||
private void joysticksend()
|
||||
{
|
||||
|
||||
@ -870,10 +948,11 @@ namespace ArdupilotMega
|
||||
|
||||
DateTime connectButtonUpdate = DateTime.Now;
|
||||
|
||||
/// <summary>
|
||||
/// Used to fix the icon status for unexpected unplugs etc...
|
||||
/// </summary>
|
||||
private void updateConnectIcon()
|
||||
{
|
||||
|
||||
|
||||
if ((DateTime.Now - connectButtonUpdate).Milliseconds > 500)
|
||||
{
|
||||
// Console.WriteLine(DateTime.Now.Millisecond);
|
||||
@ -885,8 +964,8 @@ namespace ArdupilotMega
|
||||
{
|
||||
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.disconnect;
|
||||
this.MenuConnect.BackgroundImage.Tag = "Disconnect";
|
||||
CMB_baudrate.Enabled = false;
|
||||
CMB_serialport.Enabled = false;
|
||||
_connectionControl.CMB_baudrate.Enabled = false;
|
||||
_connectionControl.CMB_serialport.Enabled = false;
|
||||
});
|
||||
}
|
||||
}
|
||||
@ -898,8 +977,8 @@ namespace ArdupilotMega
|
||||
{
|
||||
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
|
||||
this.MenuConnect.BackgroundImage.Tag = "Connect";
|
||||
CMB_baudrate.Enabled = true;
|
||||
CMB_serialport.Enabled = true;
|
||||
_connectionControl.CMB_baudrate.Enabled = true;
|
||||
_connectionControl.CMB_serialport.Enabled = true;
|
||||
});
|
||||
}
|
||||
}
|
||||
@ -907,7 +986,16 @@ namespace ArdupilotMega
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// main serial reader thread
|
||||
/// controls
|
||||
/// serial reading
|
||||
/// link quality stats
|
||||
/// speech voltage - custom - alt warning - data lost
|
||||
/// heartbeat packet sending
|
||||
///
|
||||
/// and cant fall out
|
||||
/// </summary>
|
||||
private void SerialReader()
|
||||
{
|
||||
if (serialThread == true)
|
||||
@ -1089,6 +1177,7 @@ namespace ArdupilotMega
|
||||
// for long running tasks using own threads.
|
||||
// for short use threadpool
|
||||
|
||||
// setup http server
|
||||
try
|
||||
{
|
||||
listener = new TcpListener(IPAddress.Any, 56781);
|
||||
@ -1104,6 +1193,7 @@ namespace ArdupilotMega
|
||||
CustomMessageBox.Show(ex.ToString());
|
||||
}
|
||||
|
||||
/// setup joystick packet sender
|
||||
new Thread(new ThreadStart(joysticksend))
|
||||
{
|
||||
IsBackground = true,
|
||||
@ -1111,12 +1201,14 @@ namespace ArdupilotMega
|
||||
Name = "Main joystick sender"
|
||||
}.Start();
|
||||
|
||||
// setup main serial reader
|
||||
new Thread(SerialReader)
|
||||
{
|
||||
IsBackground = true,
|
||||
Name = "Main Serial reader"
|
||||
}.Start();
|
||||
|
||||
// check for updates
|
||||
if (Debugger.IsAttached)
|
||||
{
|
||||
log.Info("Skipping update test as it appears we are debugging");
|
||||
@ -1134,6 +1226,7 @@ namespace ArdupilotMega
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
public static String ComputeWebSocketHandshakeSecurityHash09(String secWebSocketKey)
|
||||
{
|
||||
const String MagicKEY = "258EAFA5-E914-47DA-95CA-C5AB0DC85B11";
|
||||
@ -1155,7 +1248,6 @@ namespace ArdupilotMega
|
||||
/// <summary>
|
||||
/// little web server for sending network link kml's
|
||||
/// </summary>
|
||||
|
||||
void listernforclients()
|
||||
{
|
||||
try
|
||||
@ -1440,8 +1532,7 @@ namespace ArdupilotMega
|
||||
|
||||
private void TOOL_APMFirmware_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
APMFirmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), TOOL_APMFirmware.Text);
|
||||
MainV2.cs.firmware = APMFirmware;
|
||||
MainV2.cs.firmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), _connectionControl.TOOL_APMFirmware.Text);
|
||||
}
|
||||
|
||||
private void MainV2_Resize(object sender, EventArgs e)
|
||||
@ -1858,7 +1949,12 @@ namespace ArdupilotMega
|
||||
}
|
||||
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// trying to replicate google code etags....... this doesnt work.
|
||||
/// </summary>
|
||||
/// <param name="fileName"></param>
|
||||
/// <param name="modifyDate"></param>
|
||||
/// <returns></returns>
|
||||
private string GetFileETag(string fileName, DateTime modifyDate)
|
||||
{
|
||||
|
||||
@ -1892,29 +1988,34 @@ namespace ArdupilotMega
|
||||
|
||||
}
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// keyboard shortcuts override
|
||||
/// </summary>
|
||||
/// <param name="msg"></param>
|
||||
/// <param name="keyData"></param>
|
||||
/// <returns></returns>
|
||||
protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
|
||||
{
|
||||
if (keyData == (Keys.Control | Keys.F))
|
||||
if (keyData == (Keys.Control | Keys.F)) // temp
|
||||
{
|
||||
Form frm = new temp();
|
||||
ThemeManager.ApplyThemeTo(frm);
|
||||
frm.Show();
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.S))
|
||||
if (keyData == (Keys.Control | Keys.S)) // screenshot
|
||||
{
|
||||
ScreenShot();
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.G)) // test
|
||||
if (keyData == (Keys.Control | Keys.G)) // nmea out
|
||||
{
|
||||
Form frm = new SerialOutput();
|
||||
ThemeManager.ApplyThemeTo(frm);
|
||||
frm.Show();
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.A)) // test
|
||||
if (keyData == (Keys.Control | Keys.A)) // 3dr radio
|
||||
{
|
||||
Form temp = new Form();
|
||||
Control frm = new _3DRradio();
|
||||
@ -1925,7 +2026,7 @@ namespace ArdupilotMega
|
||||
temp.Show();
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.W)) // test
|
||||
if (keyData == (Keys.Control | Keys.W)) // test ac config
|
||||
{
|
||||
|
||||
Controls.ConfigPanel cfg = new Controls.ConfigPanel();
|
||||
@ -2026,7 +2127,7 @@ namespace ArdupilotMega
|
||||
return "";
|
||||
}
|
||||
|
||||
public void changeunits()
|
||||
public void ChangeUnits()
|
||||
{
|
||||
try
|
||||
{
|
||||
@ -2070,24 +2171,29 @@ namespace ArdupilotMega
|
||||
catch { }
|
||||
|
||||
}
|
||||
|
||||
private void CMB_baudrate_TextChanged(object sender, EventArgs e)
|
||||
{
|
||||
StringBuilder sb = new StringBuilder();
|
||||
int baud = 0;
|
||||
for (int i = 0; i < CMB_baudrate.Text.Length; i++)
|
||||
if (char.IsDigit(CMB_baudrate.Text[i]))
|
||||
for (int i = 0; i < _connectionControl.CMB_baudrate.Text.Length; i++)
|
||||
if (char.IsDigit(_connectionControl.CMB_baudrate.Text[i]))
|
||||
{
|
||||
sb.Append(CMB_baudrate.Text[i]);
|
||||
baud = baud * 10 + CMB_baudrate.Text[i] - '0';
|
||||
sb.Append(_connectionControl.CMB_baudrate.Text[i]);
|
||||
baud = baud * 10 + _connectionControl.CMB_baudrate.Text[i] - '0';
|
||||
}
|
||||
if (CMB_baudrate.Text != sb.ToString())
|
||||
CMB_baudrate.Text = sb.ToString();
|
||||
if (_connectionControl.CMB_baudrate.Text != sb.ToString())
|
||||
{
|
||||
_connectionControl.CMB_baudrate.Text = sb.ToString();
|
||||
}
|
||||
try
|
||||
{
|
||||
if (baud > 0 && comPort.BaseStream.BaudRate != baud)
|
||||
comPort.BaseStream.BaudRate = baud;
|
||||
}
|
||||
catch (Exception) { }
|
||||
catch (Exception)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
private void CMB_serialport_Enter(object sender, EventArgs e)
|
||||
|
@ -118,7 +118,7 @@
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<metadata name="MainMenu.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>127, 17</value>
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<data name="MainMenu.BackgroundImage" type="System.Drawing.Bitmap, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
|
@ -7,10 +7,10 @@ del installer.wixobj
|
||||
"%wix%\bin\candle" installer.wxs -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
|
||||
|
||||
|
||||
"%wix%\bin\light" installer.wixobj "%wix%\bin\difxapp_x86.wixlib" -o APMPlanner32.msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
|
||||
"%wix%\bin\light" installer.wixobj "%wix%\bin\difxapp_x86.wixlib" -o MissionPlanner32.msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
|
||||
|
||||
|
||||
"%wix%\bin\light" installer.wixobj "%wix%\bin\difxapp_x64.wixlib" -o APMPlanner64.msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
|
||||
"%wix%\bin\light" installer.wixobj "%wix%\bin\difxapp_x64.wixlib" -o MissionPlanner64.msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
|
||||
|
||||
|
||||
pause
|
||||
|
@ -2,14 +2,14 @@
|
||||
<Wix xmlns="http://schemas.microsoft.com/wix/2006/wi" xmlns:netfx="http://schemas.microsoft.com/wix/NetFxExtension" xmlns:difx="http://schemas.microsoft.com/wix/DifxAppExtension">
|
||||
|
||||
|
||||
<Product Id="*" Name="APM Planner" Language="1033" Version="1.1.68" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
|
||||
<Product Id="*" Name="APM Planner" Language="1033" Version="1.1.72" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
|
||||
|
||||
<Package Description="APM Planner Installer" Comments="Apm Planner Installer" Manufacturer="Michael Oborne" InstallerVersion="200" Compressed="yes" />
|
||||
|
||||
|
||||
<Upgrade Id="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
|
||||
<UpgradeVersion OnlyDetect="yes" Minimum="1.1.68" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" />
|
||||
<UpgradeVersion OnlyDetect="no" Maximum="1.1.68" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" />
|
||||
<UpgradeVersion OnlyDetect="yes" Minimum="1.1.72" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" />
|
||||
<UpgradeVersion OnlyDetect="no" Maximum="1.1.72" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" />
|
||||
</Upgrade>
|
||||
|
||||
<InstallExecuteSequence>
|
||||
@ -31,7 +31,7 @@
|
||||
<Permission User="Everyone" GenericAll="yes" />
|
||||
</CreateFolder>
|
||||
</Component>
|
||||
<Component Id="_comp1" Guid="5644ef2a-b056-468e-8dc6-7baa930a46e2">
|
||||
<Component Id="_comp1" Guid="ec36a99a-567a-401c-9b98-a26b885215b2">
|
||||
<File Id="_2" Source="..\bin\release\aerosim3.91.txt" />
|
||||
<File Id="_3" Source="..\bin\release\AeroSimRCAPMHil.zip" />
|
||||
<File Id="_4" Source="..\bin\release\alglibnet2.dll" />
|
||||
@ -67,191 +67,190 @@
|
||||
<File Id="_34" Source="..\bin\release\mavcmd.xml" />
|
||||
<File Id="_35" Source="..\bin\release\MAVLink.xml" />
|
||||
<File Id="_36" Source="..\bin\release\MetaDataExtractor.dll" />
|
||||
<File Id="_37" Source="..\bin\release\Microsoft.DirectX.DirectInput.dll" />
|
||||
<File Id="_38" Source="..\bin\release\Microsoft.DirectX.dll" />
|
||||
<File Id="_39" Source="..\bin\release\Microsoft.Dynamic.dll" />
|
||||
<File Id="_40" Source="..\bin\release\Microsoft.Scripting.Core.dll" />
|
||||
<File Id="_41" Source="..\bin\release\Microsoft.Scripting.Debugging.dll" />
|
||||
<File Id="_42" Source="..\bin\release\Microsoft.Scripting.dll" />
|
||||
<File Id="_43" Source="..\bin\release\Microsoft.Scripting.ExtensionAttribute.dll" />
|
||||
<File Id="_44" Source="..\bin\release\netDxf.dll" />
|
||||
<File Id="_45" Source="..\bin\release\OpenTK.dll" />
|
||||
<File Id="_46" Source="..\bin\release\OpenTK.GLControl.dll" />
|
||||
<File Id="_47" Source="..\bin\release\quadhil.xml" />
|
||||
<File Id="_48" Source="..\bin\release\serialsent.raw" />
|
||||
<File Id="_49" Source="..\bin\release\SharpKml.dll" />
|
||||
<File Id="_50" Source="..\bin\release\System.Data.SQLite.dll" />
|
||||
<File Id="_51" Source="..\bin\release\System.Speech.dll" />
|
||||
<File Id="_52" Source="..\bin\release\Updater.exe" />
|
||||
<File Id="_53" Source="..\bin\release\Updater.exe.config" />
|
||||
<File Id="_54" Source="..\bin\release\Updater.pdb" />
|
||||
<File Id="_55" Source="..\bin\release\version.exe" />
|
||||
<File Id="_56" Source="..\bin\release\version.txt" />
|
||||
<File Id="_57" Source="..\bin\release\ZedGraph.dll" />
|
||||
<File Id="_37" Source="..\bin\release\Microsoft.DirectX.dll" />
|
||||
<File Id="_38" Source="..\bin\release\Microsoft.Dynamic.dll" />
|
||||
<File Id="_39" Source="..\bin\release\Microsoft.Scripting.Core.dll" />
|
||||
<File Id="_40" Source="..\bin\release\Microsoft.Scripting.Debugging.dll" />
|
||||
<File Id="_41" Source="..\bin\release\Microsoft.Scripting.dll" />
|
||||
<File Id="_42" Source="..\bin\release\Microsoft.Scripting.ExtensionAttribute.dll" />
|
||||
<File Id="_43" Source="..\bin\release\netDxf.dll" />
|
||||
<File Id="_44" Source="..\bin\release\OpenTK.dll" />
|
||||
<File Id="_45" Source="..\bin\release\OpenTK.GLControl.dll" />
|
||||
<File Id="_46" Source="..\bin\release\quadhil.xml" />
|
||||
<File Id="_47" Source="..\bin\release\serialsent.raw" />
|
||||
<File Id="_48" Source="..\bin\release\SharpKml.dll" />
|
||||
<File Id="_49" Source="..\bin\release\System.Data.SQLite.dll" />
|
||||
<File Id="_50" Source="..\bin\release\System.Speech.dll" />
|
||||
<File Id="_51" Source="..\bin\release\Updater.exe" />
|
||||
<File Id="_52" Source="..\bin\release\Updater.exe.config" />
|
||||
<File Id="_53" Source="..\bin\release\Updater.pdb" />
|
||||
<File Id="_54" Source="..\bin\release\version.exe" />
|
||||
<File Id="_55" Source="..\bin\release\version.txt" />
|
||||
<File Id="_56" Source="..\bin\release\ZedGraph.dll" />
|
||||
</Component>
|
||||
<Directory Id="aircraft57" Name="aircraft">
|
||||
<Component Id="_comp58" Guid="7212c708-1909-4002-ba49-4f1081e32162">
|
||||
<File Id="_59" Source="..\bin\release\aircraft\placeholder.txt" />
|
||||
<Directory Id="aircraft56" Name="aircraft">
|
||||
<Component Id="_comp57" Guid="ad402273-0ee6-4774-9d32-c6851f397edd">
|
||||
<File Id="_58" Source="..\bin\release\aircraft\placeholder.txt" />
|
||||
</Component>
|
||||
<Directory Id="arducopter59" Name="arducopter">
|
||||
<Component Id="_comp60" Guid="5f433433-26df-44a9-b9c9-89aa3397030d">
|
||||
<File Id="_61" Source="..\bin\release\aircraft\arducopter\arducopter-set.xml" />
|
||||
<File Id="_62" Source="..\bin\release\aircraft\arducopter\arducopter.jpg" />
|
||||
<File Id="_63" Source="..\bin\release\aircraft\arducopter\arducopter.xml" />
|
||||
<File Id="_64" Source="..\bin\release\aircraft\arducopter\initfile.xml" />
|
||||
<File Id="_65" Source="..\bin\release\aircraft\arducopter\plus_quad2-set.xml" />
|
||||
<File Id="_66" Source="..\bin\release\aircraft\arducopter\plus_quad2.xml" />
|
||||
<File Id="_67" Source="..\bin\release\aircraft\arducopter\quad.nas" />
|
||||
<File Id="_68" Source="..\bin\release\aircraft\arducopter\README" />
|
||||
<Directory Id="arducopter58" Name="arducopter">
|
||||
<Component Id="_comp59" Guid="dba0cbb2-b6e5-446a-a279-5c5215cb9415">
|
||||
<File Id="_60" Source="..\bin\release\aircraft\arducopter\arducopter-set.xml" />
|
||||
<File Id="_61" Source="..\bin\release\aircraft\arducopter\arducopter.jpg" />
|
||||
<File Id="_62" Source="..\bin\release\aircraft\arducopter\arducopter.xml" />
|
||||
<File Id="_63" Source="..\bin\release\aircraft\arducopter\initfile.xml" />
|
||||
<File Id="_64" Source="..\bin\release\aircraft\arducopter\plus_quad2-set.xml" />
|
||||
<File Id="_65" Source="..\bin\release\aircraft\arducopter\plus_quad2.xml" />
|
||||
<File Id="_66" Source="..\bin\release\aircraft\arducopter\quad.nas" />
|
||||
<File Id="_67" Source="..\bin\release\aircraft\arducopter\README" />
|
||||
</Component>
|
||||
<Directory Id="data68" Name="data">
|
||||
<Component Id="_comp69" Guid="26f173bd-765b-43ba-8d28-2617728dfb2c">
|
||||
<File Id="_70" Source="..\bin\release\aircraft\arducopter\data\arducopter_half_step.txt" />
|
||||
<File Id="_71" Source="..\bin\release\aircraft\arducopter\data\arducopter_step.txt" />
|
||||
<File Id="_72" Source="..\bin\release\aircraft\arducopter\data\rw_generic_pylon.ac" />
|
||||
<Directory Id="data67" Name="data">
|
||||
<Component Id="_comp68" Guid="4ad7018b-700d-4c21-a0df-830691c9e9f1">
|
||||
<File Id="_69" Source="..\bin\release\aircraft\arducopter\data\arducopter_half_step.txt" />
|
||||
<File Id="_70" Source="..\bin\release\aircraft\arducopter\data\arducopter_step.txt" />
|
||||
<File Id="_71" Source="..\bin\release\aircraft\arducopter\data\rw_generic_pylon.ac" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Engines72" Name="Engines">
|
||||
<Component Id="_comp73" Guid="a0806084-173b-4ff2-969e-4ce5903d0d5f">
|
||||
<File Id="_74" Source="..\bin\release\aircraft\arducopter\Engines\a2830-12.xml" />
|
||||
<File Id="_75" Source="..\bin\release\aircraft\arducopter\Engines\prop10x4.5.xml" />
|
||||
<Directory Id="Engines71" Name="Engines">
|
||||
<Component Id="_comp72" Guid="42d52dcf-ca6b-4d34-ba01-2d10198462f7">
|
||||
<File Id="_73" Source="..\bin\release\aircraft\arducopter\Engines\a2830-12.xml" />
|
||||
<File Id="_74" Source="..\bin\release\aircraft\arducopter\Engines\prop10x4.5.xml" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Models75" Name="Models">
|
||||
<Component Id="_comp76" Guid="1d1b8579-fe0d-49a5-b3b5-028fc65f3151">
|
||||
<File Id="_77" Source="..\bin\release\aircraft\arducopter\Models\arducopter.ac" />
|
||||
<File Id="_78" Source="..\bin\release\aircraft\arducopter\Models\arducopter.xml" />
|
||||
<File Id="_79" Source="..\bin\release\aircraft\arducopter\Models\plus_quad.ac" />
|
||||
<File Id="_80" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.ac" />
|
||||
<File Id="_81" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.xml" />
|
||||
<File Id="_82" Source="..\bin\release\aircraft\arducopter\Models\quad.3ds" />
|
||||
<File Id="_83" Source="..\bin\release\aircraft\arducopter\Models\shareware_output.3ds" />
|
||||
<File Id="_84" Source="..\bin\release\aircraft\arducopter\Models\Untitled.ac" />
|
||||
<File Id="_85" Source="..\bin\release\aircraft\arducopter\Models\Y6_test.ac" />
|
||||
<Directory Id="Models74" Name="Models">
|
||||
<Component Id="_comp75" Guid="c1c7bb9f-d9ff-4efe-ad9a-d87dcf798f55">
|
||||
<File Id="_76" Source="..\bin\release\aircraft\arducopter\Models\arducopter.ac" />
|
||||
<File Id="_77" Source="..\bin\release\aircraft\arducopter\Models\arducopter.xml" />
|
||||
<File Id="_78" Source="..\bin\release\aircraft\arducopter\Models\plus_quad.ac" />
|
||||
<File Id="_79" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.ac" />
|
||||
<File Id="_80" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.xml" />
|
||||
<File Id="_81" Source="..\bin\release\aircraft\arducopter\Models\quad.3ds" />
|
||||
<File Id="_82" Source="..\bin\release\aircraft\arducopter\Models\shareware_output.3ds" />
|
||||
<File Id="_83" Source="..\bin\release\aircraft\arducopter\Models\Untitled.ac" />
|
||||
<File Id="_84" Source="..\bin\release\aircraft\arducopter\Models\Y6_test.ac" />
|
||||
</Component>
|
||||
</Directory>
|
||||
</Directory>
|
||||
<Directory Id="Rascal85" Name="Rascal">
|
||||
<Component Id="_comp86" Guid="5dfbf7cf-8aa2-4837-88f0-c036f532d722">
|
||||
<File Id="_87" Source="..\bin\release\aircraft\Rascal\Rascal-keyboard.xml" />
|
||||
<File Id="_88" Source="..\bin\release\aircraft\Rascal\Rascal-submodels.xml" />
|
||||
<File Id="_89" Source="..\bin\release\aircraft\Rascal\Rascal.xml" />
|
||||
<File Id="_90" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim-set.xml" />
|
||||
<File Id="_91" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim.xml" />
|
||||
<File Id="_92" Source="..\bin\release\aircraft\Rascal\Rascal110-splash.rgb" />
|
||||
<File Id="_93" Source="..\bin\release\aircraft\Rascal\README.Rascal" />
|
||||
<File Id="_94" Source="..\bin\release\aircraft\Rascal\reset_CMAC.xml" />
|
||||
<File Id="_95" Source="..\bin\release\aircraft\Rascal\thumbnail.jpg" />
|
||||
<Directory Id="Rascal84" Name="Rascal">
|
||||
<Component Id="_comp85" Guid="9735238e-339f-420e-9821-4724c17039e8">
|
||||
<File Id="_86" Source="..\bin\release\aircraft\Rascal\Rascal-keyboard.xml" />
|
||||
<File Id="_87" Source="..\bin\release\aircraft\Rascal\Rascal-submodels.xml" />
|
||||
<File Id="_88" Source="..\bin\release\aircraft\Rascal\Rascal.xml" />
|
||||
<File Id="_89" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim-set.xml" />
|
||||
<File Id="_90" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim.xml" />
|
||||
<File Id="_91" Source="..\bin\release\aircraft\Rascal\Rascal110-splash.rgb" />
|
||||
<File Id="_92" Source="..\bin\release\aircraft\Rascal\README.Rascal" />
|
||||
<File Id="_93" Source="..\bin\release\aircraft\Rascal\reset_CMAC.xml" />
|
||||
<File Id="_94" Source="..\bin\release\aircraft\Rascal\thumbnail.jpg" />
|
||||
</Component>
|
||||
<Directory Id="Dialogs95" Name="Dialogs">
|
||||
<Component Id="_comp96" Guid="b5c4167d-062e-43c6-b97f-18bfbfaa8f31">
|
||||
<File Id="_97" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml" />
|
||||
<File Id="_98" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml.new" />
|
||||
<Directory Id="Dialogs94" Name="Dialogs">
|
||||
<Component Id="_comp95" Guid="f0b6ef61-b6cc-4d5a-8354-74b08e010ff1">
|
||||
<File Id="_96" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml" />
|
||||
<File Id="_97" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml.new" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Engines98" Name="Engines">
|
||||
<Component Id="_comp99" Guid="76fcc1e7-b39d-4335-8af2-6c13643c8725">
|
||||
<File Id="_100" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml" />
|
||||
<File Id="_101" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml.new" />
|
||||
<File Id="_102" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml" />
|
||||
<File Id="_103" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml.new" />
|
||||
<Directory Id="Engines97" Name="Engines">
|
||||
<Component Id="_comp98" Guid="0c770102-701e-4f2c-9e29-7399484615a1">
|
||||
<File Id="_99" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml" />
|
||||
<File Id="_100" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml.new" />
|
||||
<File Id="_101" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml" />
|
||||
<File Id="_102" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml.new" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Models103" Name="Models">
|
||||
<Component Id="_comp104" Guid="c7c50e85-8e0a-4e79-b62f-b5b200315146">
|
||||
<File Id="_105" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb" />
|
||||
<File Id="_106" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb.new" />
|
||||
<File Id="_107" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac" />
|
||||
<File Id="_108" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac.new" />
|
||||
<File Id="_109" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml" />
|
||||
<File Id="_110" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml.new" />
|
||||
<File Id="_111" Source="..\bin\release\aircraft\Rascal\Models\smoke.png" />
|
||||
<File Id="_112" Source="..\bin\release\aircraft\Rascal\Models\smoke.png.new" />
|
||||
<File Id="_113" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml" />
|
||||
<File Id="_114" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml.new" />
|
||||
<File Id="_115" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac" />
|
||||
<File Id="_116" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac.new" />
|
||||
<File Id="_117" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml" />
|
||||
<File Id="_118" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml.new" />
|
||||
<Directory Id="Models102" Name="Models">
|
||||
<Component Id="_comp103" Guid="b1b6e457-631f-4a1b-9147-bf398e803c03">
|
||||
<File Id="_104" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb" />
|
||||
<File Id="_105" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb.new" />
|
||||
<File Id="_106" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac" />
|
||||
<File Id="_107" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac.new" />
|
||||
<File Id="_108" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml" />
|
||||
<File Id="_109" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml.new" />
|
||||
<File Id="_110" Source="..\bin\release\aircraft\Rascal\Models\smoke.png" />
|
||||
<File Id="_111" Source="..\bin\release\aircraft\Rascal\Models\smoke.png.new" />
|
||||
<File Id="_112" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml" />
|
||||
<File Id="_113" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml.new" />
|
||||
<File Id="_114" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac" />
|
||||
<File Id="_115" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac.new" />
|
||||
<File Id="_116" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml" />
|
||||
<File Id="_117" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml.new" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Systems118" Name="Systems">
|
||||
<Component Id="_comp119" Guid="0ecaf32f-1460-4a1a-a17b-74d3a0995b93">
|
||||
<File Id="_120" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml" />
|
||||
<File Id="_121" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml.new" />
|
||||
<File Id="_122" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas" />
|
||||
<File Id="_123" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas.new" />
|
||||
<File Id="_124" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml" />
|
||||
<File Id="_125" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml.new" />
|
||||
<File Id="_126" Source="..\bin\release\aircraft\Rascal\Systems\main.nas" />
|
||||
<File Id="_127" Source="..\bin\release\aircraft\Rascal\Systems\main.nas.new" />
|
||||
<File Id="_128" Source="..\bin\release\aircraft\Rascal\Systems\ugear.nas" />
|
||||
<Directory Id="Systems117" Name="Systems">
|
||||
<Component Id="_comp118" Guid="07ca2fcc-1f36-4a90-867e-9a5b2effbbd6">
|
||||
<File Id="_119" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml" />
|
||||
<File Id="_120" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml.new" />
|
||||
<File Id="_121" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas" />
|
||||
<File Id="_122" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas.new" />
|
||||
<File Id="_123" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml" />
|
||||
<File Id="_124" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml.new" />
|
||||
<File Id="_125" Source="..\bin\release\aircraft\Rascal\Systems\main.nas" />
|
||||
<File Id="_126" Source="..\bin\release\aircraft\Rascal\Systems\main.nas.new" />
|
||||
<File Id="_127" Source="..\bin\release\aircraft\Rascal\Systems\ugear.nas" />
|
||||
</Component>
|
||||
</Directory>
|
||||
</Directory>
|
||||
</Directory>
|
||||
<Directory Id="Driver128" Name="Driver">
|
||||
<Component Id="_comp129" Guid="515e59db-299e-4863-a730-ffd0ef02483b">
|
||||
<File Id="_130" Source="..\bin\release\Driver\Arduino MEGA 2560.inf" />
|
||||
<File Id="_131" Source="..\bin\release\Driver\Arduino MEGA 2560.inf.new" />
|
||||
<Directory Id="Driver127" Name="Driver">
|
||||
<Component Id="_comp128" Guid="5797f8f3-d966-4875-a5f7-c75bcaf7254e">
|
||||
<File Id="_129" Source="..\bin\release\Driver\Arduino MEGA 2560.inf" />
|
||||
<File Id="_130" Source="..\bin\release\Driver\Arduino MEGA 2560.inf.new" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="es_ES131" Name="es-ES">
|
||||
<Component Id="_comp132" Guid="04d19c2c-1174-462d-855e-454f99b4dd33">
|
||||
<File Id="_133" Source="..\bin\release\es-ES\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="es_ES130" Name="es-ES">
|
||||
<Component Id="_comp131" Guid="d96f8317-0a0a-402d-9450-52ed96582ba9">
|
||||
<File Id="_132" Source="..\bin\release\es-ES\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="fr133" Name="fr">
|
||||
<Component Id="_comp134" Guid="c7e73622-81d5-4c92-903e-b71c8d69f7d2">
|
||||
<File Id="_135" Source="..\bin\release\fr\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="fr132" Name="fr">
|
||||
<Component Id="_comp133" Guid="27919138-6492-4f44-a50e-1482c0c4846c">
|
||||
<File Id="_134" Source="..\bin\release\fr\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="it_IT135" Name="it-IT">
|
||||
<Component Id="_comp136" Guid="64d73ea4-50e4-4379-8915-50d314fc680c">
|
||||
<File Id="_137" Source="..\bin\release\it-IT\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="it_IT134" Name="it-IT">
|
||||
<Component Id="_comp135" Guid="f494900f-d167-416d-9e2e-25392641f148">
|
||||
<File Id="_136" Source="..\bin\release\it-IT\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="jsbsim137" Name="jsbsim">
|
||||
<Component Id="_comp138" Guid="6584d317-3e83-4525-a2d8-48361fd6cced">
|
||||
<File Id="_139" Source="..\bin\release\jsbsim\fgout.xml" />
|
||||
<File Id="_140" Source="..\bin\release\jsbsim\rascal_test.xml" />
|
||||
<Directory Id="jsbsim136" Name="jsbsim">
|
||||
<Component Id="_comp137" Guid="28d5005d-14cd-472f-a68d-a5e175ca1433">
|
||||
<File Id="_138" Source="..\bin\release\jsbsim\fgout.xml" />
|
||||
<File Id="_139" Source="..\bin\release\jsbsim\rascal_test.xml" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="m3u140" Name="m3u">
|
||||
<Component Id="_comp141" Guid="e067cb13-59c1-44c2-b632-1c73d3da5dda">
|
||||
<File Id="_142" Source="..\bin\release\m3u\both.m3u" />
|
||||
<File Id="_143" Source="..\bin\release\m3u\GeoRefnetworklink.kml" />
|
||||
<File Id="_144" Source="..\bin\release\m3u\hud.m3u" />
|
||||
<File Id="_145" Source="..\bin\release\m3u\map.m3u" />
|
||||
<File Id="_146" Source="..\bin\release\m3u\networklink.kml" />
|
||||
<Directory Id="m3u139" Name="m3u">
|
||||
<Component Id="_comp140" Guid="84cd93b9-cc19-4436-8617-6462de04ee92">
|
||||
<File Id="_141" Source="..\bin\release\m3u\both.m3u" />
|
||||
<File Id="_142" Source="..\bin\release\m3u\GeoRefnetworklink.kml" />
|
||||
<File Id="_143" Source="..\bin\release\m3u\hud.m3u" />
|
||||
<File Id="_144" Source="..\bin\release\m3u\map.m3u" />
|
||||
<File Id="_145" Source="..\bin\release\m3u\networklink.kml" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="pl146" Name="pl">
|
||||
<Component Id="_comp147" Guid="c9dc4142-0fe8-4804-9cc1-97b669c6bb70">
|
||||
<File Id="_148" Source="..\bin\release\pl\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="pl145" Name="pl">
|
||||
<Component Id="_comp146" Guid="bb8d116b-93d2-42a2-b792-97d4f0ba7916">
|
||||
<File Id="_147" Source="..\bin\release\pl\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Resources148" Name="Resources">
|
||||
<Component Id="_comp149" Guid="ed3e0985-9010-4930-b36e-9be84fcbe408">
|
||||
<File Id="_150" Source="..\bin\release\Resources\MAVCmd.txt" />
|
||||
<File Id="_151" Source="..\bin\release\Resources\MAVCmd.txt.new" />
|
||||
<File Id="_152" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf" />
|
||||
<File Id="_153" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf.new" />
|
||||
<Directory Id="Resources147" Name="Resources">
|
||||
<Component Id="_comp148" Guid="7ea8725a-12b4-4420-8993-a572ba8a5125">
|
||||
<File Id="_149" Source="..\bin\release\Resources\MAVCmd.txt" />
|
||||
<File Id="_150" Source="..\bin\release\Resources\MAVCmd.txt.new" />
|
||||
<File Id="_151" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf" />
|
||||
<File Id="_152" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf.new" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="ru_RU153" Name="ru-RU">
|
||||
<Component Id="_comp154" Guid="2e0e6d6d-370a-4c2c-9331-e941060675bc">
|
||||
<File Id="_155" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="ru_RU152" Name="ru-RU">
|
||||
<Component Id="_comp153" Guid="6960bab7-cc6b-4eaf-9ebb-2f26af194dbf">
|
||||
<File Id="_154" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="zh_Hans155" Name="zh-Hans">
|
||||
<Component Id="_comp156" Guid="381a4296-5113-4d10-880a-bd6bb6dbfe20">
|
||||
<File Id="_157" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="zh_Hans154" Name="zh-Hans">
|
||||
<Component Id="_comp155" Guid="bb5d655e-55ef-4d92-9e9c-6595387e27c9">
|
||||
<File Id="_156" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="zh_TW157" Name="zh-TW">
|
||||
<Component Id="_comp158" Guid="c49d6f3f-8616-483e-9cf7-e6685b9fc785">
|
||||
<File Id="_159" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="zh_TW156" Name="zh-TW">
|
||||
<Component Id="_comp157" Guid="509bcc10-ad13-46dc-917e-2086fe5bac44">
|
||||
<File Id="_158" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
|
||||
@ -293,27 +292,27 @@
|
||||
<ComponentRef Id="InstallDirPermissions" />
|
||||
|
||||
<ComponentRef Id="_comp1" />
|
||||
<ComponentRef Id="_comp58" />
|
||||
<ComponentRef Id="_comp60" />
|
||||
<ComponentRef Id="_comp69" />
|
||||
<ComponentRef Id="_comp73" />
|
||||
<ComponentRef Id="_comp76" />
|
||||
<ComponentRef Id="_comp86" />
|
||||
<ComponentRef Id="_comp96" />
|
||||
<ComponentRef Id="_comp99" />
|
||||
<ComponentRef Id="_comp104" />
|
||||
<ComponentRef Id="_comp119" />
|
||||
<ComponentRef Id="_comp129" />
|
||||
<ComponentRef Id="_comp132" />
|
||||
<ComponentRef Id="_comp134" />
|
||||
<ComponentRef Id="_comp136" />
|
||||
<ComponentRef Id="_comp138" />
|
||||
<ComponentRef Id="_comp141" />
|
||||
<ComponentRef Id="_comp147" />
|
||||
<ComponentRef Id="_comp149" />
|
||||
<ComponentRef Id="_comp154" />
|
||||
<ComponentRef Id="_comp156" />
|
||||
<ComponentRef Id="_comp158" />
|
||||
<ComponentRef Id="_comp57" />
|
||||
<ComponentRef Id="_comp59" />
|
||||
<ComponentRef Id="_comp68" />
|
||||
<ComponentRef Id="_comp72" />
|
||||
<ComponentRef Id="_comp75" />
|
||||
<ComponentRef Id="_comp85" />
|
||||
<ComponentRef Id="_comp95" />
|
||||
<ComponentRef Id="_comp98" />
|
||||
<ComponentRef Id="_comp103" />
|
||||
<ComponentRef Id="_comp118" />
|
||||
<ComponentRef Id="_comp128" />
|
||||
<ComponentRef Id="_comp131" />
|
||||
<ComponentRef Id="_comp133" />
|
||||
<ComponentRef Id="_comp135" />
|
||||
<ComponentRef Id="_comp137" />
|
||||
<ComponentRef Id="_comp140" />
|
||||
<ComponentRef Id="_comp146" />
|
||||
<ComponentRef Id="_comp148" />
|
||||
<ComponentRef Id="_comp153" />
|
||||
<ComponentRef Id="_comp155" />
|
||||
<ComponentRef Id="_comp157" />
|
||||
|
||||
|
||||
<ComponentRef Id="ApplicationShortcut" />
|
||||
|
Binary file not shown.
@ -34,5 +34,5 @@ using System.Resources;
|
||||
// by using the '*' as shown below:
|
||||
// [assembly: AssemblyVersion("1.0.*")]
|
||||
[assembly: AssemblyVersion("1.1.*")]
|
||||
[assembly: AssemblyFileVersion("1.1.71")]
|
||||
[assembly: AssemblyFileVersion("1.1.73")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
391
Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
generated
391
Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
generated
@ -56,6 +56,16 @@
|
||||
this.RS2 = new System.Windows.Forms.ComboBox();
|
||||
this.RS1 = new System.Windows.Forms.ComboBox();
|
||||
this.RSSI = new System.Windows.Forms.TextBox();
|
||||
this.S10 = new System.Windows.Forms.ComboBox();
|
||||
this.S11 = new System.Windows.Forms.ComboBox();
|
||||
this.S12 = new System.Windows.Forms.ComboBox();
|
||||
this.RS12 = new System.Windows.Forms.ComboBox();
|
||||
this.RS11 = new System.Windows.Forms.ComboBox();
|
||||
this.RS10 = new System.Windows.Forms.ComboBox();
|
||||
this.S9 = new System.Windows.Forms.ComboBox();
|
||||
this.S8 = new System.Windows.Forms.ComboBox();
|
||||
this.RS8 = new System.Windows.Forms.ComboBox();
|
||||
this.RS9 = new System.Windows.Forms.ComboBox();
|
||||
this.RS0 = new System.Windows.Forms.TextBox();
|
||||
this.label9 = new System.Windows.Forms.Label();
|
||||
this.label10 = new System.Windows.Forms.Label();
|
||||
@ -70,6 +80,27 @@
|
||||
this.BUT_syncS2 = new ArdupilotMega.MyButton();
|
||||
this.BUT_syncS3 = new ArdupilotMega.MyButton();
|
||||
this.BUT_syncS5 = new ArdupilotMega.MyButton();
|
||||
this.label13 = new System.Windows.Forms.Label();
|
||||
this.label14 = new System.Windows.Forms.Label();
|
||||
this.label15 = new System.Windows.Forms.Label();
|
||||
this.label16 = new System.Windows.Forms.Label();
|
||||
this.label17 = new System.Windows.Forms.Label();
|
||||
this.label20 = new System.Windows.Forms.Label();
|
||||
this.label21 = new System.Windows.Forms.Label();
|
||||
this.label22 = new System.Windows.Forms.Label();
|
||||
this.label23 = new System.Windows.Forms.Label();
|
||||
this.label24 = new System.Windows.Forms.Label();
|
||||
this.label25 = new System.Windows.Forms.Label();
|
||||
this.label26 = new System.Windows.Forms.Label();
|
||||
this.label27 = new System.Windows.Forms.Label();
|
||||
this.label28 = new System.Windows.Forms.Label();
|
||||
this.label29 = new System.Windows.Forms.Label();
|
||||
this.label30 = new System.Windows.Forms.Label();
|
||||
this.label31 = new System.Windows.Forms.Label();
|
||||
this.label32 = new System.Windows.Forms.Label();
|
||||
this.BUT_syncS8 = new ArdupilotMega.MyButton();
|
||||
this.BUT_syncS9 = new ArdupilotMega.MyButton();
|
||||
this.BUT_syncS10 = new ArdupilotMega.MyButton();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// Progressbar
|
||||
@ -263,6 +294,7 @@
|
||||
//
|
||||
// RS4
|
||||
//
|
||||
resources.ApplyResources(this.RS4, "RS4");
|
||||
this.RS4.FormattingEnabled = true;
|
||||
this.RS4.Items.AddRange(new object[] {
|
||||
resources.GetString("RS4.Items"),
|
||||
@ -286,12 +318,12 @@
|
||||
resources.GetString("RS4.Items18"),
|
||||
resources.GetString("RS4.Items19"),
|
||||
resources.GetString("RS4.Items20")});
|
||||
resources.ApplyResources(this.RS4, "RS4");
|
||||
this.RS4.Name = "RS4";
|
||||
this.toolTip1.SetToolTip(this.RS4, resources.GetString("RS4.ToolTip"));
|
||||
//
|
||||
// RS3
|
||||
//
|
||||
resources.ApplyResources(this.RS3, "RS3");
|
||||
this.RS3.FormattingEnabled = true;
|
||||
this.RS3.Items.AddRange(new object[] {
|
||||
resources.GetString("RS3.Items"),
|
||||
@ -324,12 +356,12 @@
|
||||
resources.GetString("RS3.Items27"),
|
||||
resources.GetString("RS3.Items28"),
|
||||
resources.GetString("RS3.Items29")});
|
||||
resources.ApplyResources(this.RS3, "RS3");
|
||||
this.RS3.Name = "RS3";
|
||||
this.toolTip1.SetToolTip(this.RS3, resources.GetString("RS3.ToolTip"));
|
||||
//
|
||||
// RS2
|
||||
//
|
||||
resources.ApplyResources(this.RS2, "RS2");
|
||||
this.RS2.FormattingEnabled = true;
|
||||
this.RS2.Items.AddRange(new object[] {
|
||||
resources.GetString("RS2.Items"),
|
||||
@ -342,12 +374,12 @@
|
||||
resources.GetString("RS2.Items7"),
|
||||
resources.GetString("RS2.Items8"),
|
||||
resources.GetString("RS2.Items9")});
|
||||
resources.ApplyResources(this.RS2, "RS2");
|
||||
this.RS2.Name = "RS2";
|
||||
this.toolTip1.SetToolTip(this.RS2, resources.GetString("RS2.ToolTip"));
|
||||
//
|
||||
// RS1
|
||||
//
|
||||
resources.ApplyResources(this.RS1, "RS1");
|
||||
this.RS1.FormattingEnabled = true;
|
||||
this.RS1.Items.AddRange(new object[] {
|
||||
resources.GetString("RS1.Items"),
|
||||
@ -359,7 +391,6 @@
|
||||
resources.GetString("RS1.Items6"),
|
||||
resources.GetString("RS1.Items7"),
|
||||
resources.GetString("RS1.Items8")});
|
||||
resources.ApplyResources(this.RS1, "RS1");
|
||||
this.RS1.Name = "RS1";
|
||||
this.toolTip1.SetToolTip(this.RS1, resources.GetString("RS1.ToolTip"));
|
||||
//
|
||||
@ -370,6 +401,183 @@
|
||||
this.RSSI.ReadOnly = true;
|
||||
this.toolTip1.SetToolTip(this.RSSI, resources.GetString("RSSI.ToolTip"));
|
||||
//
|
||||
// S10
|
||||
//
|
||||
this.S10.FormattingEnabled = true;
|
||||
this.S10.Items.AddRange(new object[] {
|
||||
resources.GetString("S10.Items"),
|
||||
resources.GetString("S10.Items1"),
|
||||
resources.GetString("S10.Items2"),
|
||||
resources.GetString("S10.Items3"),
|
||||
resources.GetString("S10.Items4"),
|
||||
resources.GetString("S10.Items5"),
|
||||
resources.GetString("S10.Items6"),
|
||||
resources.GetString("S10.Items7"),
|
||||
resources.GetString("S10.Items8"),
|
||||
resources.GetString("S10.Items9"),
|
||||
resources.GetString("S10.Items10"),
|
||||
resources.GetString("S10.Items11"),
|
||||
resources.GetString("S10.Items12"),
|
||||
resources.GetString("S10.Items13"),
|
||||
resources.GetString("S10.Items14"),
|
||||
resources.GetString("S10.Items15"),
|
||||
resources.GetString("S10.Items16"),
|
||||
resources.GetString("S10.Items17"),
|
||||
resources.GetString("S10.Items18")});
|
||||
resources.ApplyResources(this.S10, "S10");
|
||||
this.S10.Name = "S10";
|
||||
this.toolTip1.SetToolTip(this.S10, resources.GetString("S10.ToolTip"));
|
||||
//
|
||||
// S11
|
||||
//
|
||||
this.S11.FormattingEnabled = true;
|
||||
this.S11.Items.AddRange(new object[] {
|
||||
resources.GetString("S11.Items"),
|
||||
resources.GetString("S11.Items1"),
|
||||
resources.GetString("S11.Items2"),
|
||||
resources.GetString("S11.Items3"),
|
||||
resources.GetString("S11.Items4"),
|
||||
resources.GetString("S11.Items5"),
|
||||
resources.GetString("S11.Items6"),
|
||||
resources.GetString("S11.Items7"),
|
||||
resources.GetString("S11.Items8"),
|
||||
resources.GetString("S11.Items9")});
|
||||
resources.ApplyResources(this.S11, "S11");
|
||||
this.S11.Name = "S11";
|
||||
this.toolTip1.SetToolTip(this.S11, resources.GetString("S11.ToolTip"));
|
||||
//
|
||||
// S12
|
||||
//
|
||||
this.S12.FormattingEnabled = true;
|
||||
this.S12.Items.AddRange(new object[] {
|
||||
resources.GetString("S12.Items"),
|
||||
resources.GetString("S12.Items1")});
|
||||
resources.ApplyResources(this.S12, "S12");
|
||||
this.S12.Name = "S12";
|
||||
this.toolTip1.SetToolTip(this.S12, resources.GetString("S12.ToolTip"));
|
||||
//
|
||||
// RS12
|
||||
//
|
||||
resources.ApplyResources(this.RS12, "RS12");
|
||||
this.RS12.FormattingEnabled = true;
|
||||
this.RS12.Items.AddRange(new object[] {
|
||||
resources.GetString("RS12.Items"),
|
||||
resources.GetString("RS12.Items1")});
|
||||
this.RS12.Name = "RS12";
|
||||
this.toolTip1.SetToolTip(this.RS12, resources.GetString("RS12.ToolTip"));
|
||||
//
|
||||
// RS11
|
||||
//
|
||||
resources.ApplyResources(this.RS11, "RS11");
|
||||
this.RS11.FormattingEnabled = true;
|
||||
this.RS11.Items.AddRange(new object[] {
|
||||
resources.GetString("RS11.Items"),
|
||||
resources.GetString("RS11.Items1"),
|
||||
resources.GetString("RS11.Items2"),
|
||||
resources.GetString("RS11.Items3"),
|
||||
resources.GetString("RS11.Items4"),
|
||||
resources.GetString("RS11.Items5"),
|
||||
resources.GetString("RS11.Items6"),
|
||||
resources.GetString("RS11.Items7"),
|
||||
resources.GetString("RS11.Items8"),
|
||||
resources.GetString("RS11.Items9")});
|
||||
this.RS11.Name = "RS11";
|
||||
this.toolTip1.SetToolTip(this.RS11, resources.GetString("RS11.ToolTip"));
|
||||
//
|
||||
// RS10
|
||||
//
|
||||
resources.ApplyResources(this.RS10, "RS10");
|
||||
this.RS10.FormattingEnabled = true;
|
||||
this.RS10.Items.AddRange(new object[] {
|
||||
resources.GetString("RS10.Items"),
|
||||
resources.GetString("RS10.Items1"),
|
||||
resources.GetString("RS10.Items2"),
|
||||
resources.GetString("RS10.Items3"),
|
||||
resources.GetString("RS10.Items4"),
|
||||
resources.GetString("RS10.Items5"),
|
||||
resources.GetString("RS10.Items6"),
|
||||
resources.GetString("RS10.Items7"),
|
||||
resources.GetString("RS10.Items8"),
|
||||
resources.GetString("RS10.Items9"),
|
||||
resources.GetString("RS10.Items10"),
|
||||
resources.GetString("RS10.Items11"),
|
||||
resources.GetString("RS10.Items12"),
|
||||
resources.GetString("RS10.Items13"),
|
||||
resources.GetString("RS10.Items14"),
|
||||
resources.GetString("RS10.Items15"),
|
||||
resources.GetString("RS10.Items16"),
|
||||
resources.GetString("RS10.Items17"),
|
||||
resources.GetString("RS10.Items18")});
|
||||
this.RS10.Name = "RS10";
|
||||
this.toolTip1.SetToolTip(this.RS10, resources.GetString("RS10.ToolTip"));
|
||||
//
|
||||
// S9
|
||||
//
|
||||
this.S9.FormattingEnabled = true;
|
||||
this.S9.Items.AddRange(new object[] {
|
||||
resources.GetString("S9.Items"),
|
||||
resources.GetString("S9.Items1"),
|
||||
resources.GetString("S9.Items2"),
|
||||
resources.GetString("S9.Items3"),
|
||||
resources.GetString("S9.Items4"),
|
||||
resources.GetString("S9.Items5"),
|
||||
resources.GetString("S9.Items6"),
|
||||
resources.GetString("S9.Items7"),
|
||||
resources.GetString("S9.Items8")});
|
||||
resources.ApplyResources(this.S9, "S9");
|
||||
this.S9.Name = "S9";
|
||||
//
|
||||
// S8
|
||||
//
|
||||
this.S8.FormattingEnabled = true;
|
||||
this.S8.Items.AddRange(new object[] {
|
||||
resources.GetString("S8.Items"),
|
||||
resources.GetString("S8.Items1"),
|
||||
resources.GetString("S8.Items2"),
|
||||
resources.GetString("S8.Items3"),
|
||||
resources.GetString("S8.Items4"),
|
||||
resources.GetString("S8.Items5"),
|
||||
resources.GetString("S8.Items6"),
|
||||
resources.GetString("S8.Items7"),
|
||||
resources.GetString("S8.Items8"),
|
||||
resources.GetString("S8.Items9"),
|
||||
resources.GetString("S8.Items10"),
|
||||
resources.GetString("S8.Items11")});
|
||||
resources.ApplyResources(this.S8, "S8");
|
||||
this.S8.Name = "S8";
|
||||
//
|
||||
// RS8
|
||||
//
|
||||
resources.ApplyResources(this.RS8, "RS8");
|
||||
this.RS8.FormattingEnabled = true;
|
||||
this.RS8.Items.AddRange(new object[] {
|
||||
resources.GetString("RS8.Items"),
|
||||
resources.GetString("RS8.Items1"),
|
||||
resources.GetString("RS8.Items2"),
|
||||
resources.GetString("RS8.Items3"),
|
||||
resources.GetString("RS8.Items4"),
|
||||
resources.GetString("RS8.Items5"),
|
||||
resources.GetString("RS8.Items6"),
|
||||
resources.GetString("RS8.Items7"),
|
||||
resources.GetString("RS8.Items8")});
|
||||
this.RS8.Name = "RS8";
|
||||
//
|
||||
// RS9
|
||||
//
|
||||
resources.ApplyResources(this.RS9, "RS9");
|
||||
this.RS9.FormattingEnabled = true;
|
||||
this.RS9.Items.AddRange(new object[] {
|
||||
resources.GetString("RS9.Items"),
|
||||
resources.GetString("RS9.Items1"),
|
||||
resources.GetString("RS9.Items2"),
|
||||
resources.GetString("RS9.Items3"),
|
||||
resources.GetString("RS9.Items4"),
|
||||
resources.GetString("RS9.Items5"),
|
||||
resources.GetString("RS9.Items6"),
|
||||
resources.GetString("RS9.Items7"),
|
||||
resources.GetString("RS9.Items8")});
|
||||
this.RS9.Name = "RS9";
|
||||
//
|
||||
// RS0
|
||||
//
|
||||
resources.ApplyResources(this.RS0, "RS0");
|
||||
@ -456,10 +664,152 @@
|
||||
this.BUT_syncS5.UseVisualStyleBackColor = true;
|
||||
this.BUT_syncS5.Click += new System.EventHandler(this.BUT_syncS5_Click);
|
||||
//
|
||||
// label13
|
||||
//
|
||||
resources.ApplyResources(this.label13, "label13");
|
||||
this.label13.Name = "label13";
|
||||
//
|
||||
// label14
|
||||
//
|
||||
resources.ApplyResources(this.label14, "label14");
|
||||
this.label14.Name = "label14";
|
||||
//
|
||||
// label15
|
||||
//
|
||||
resources.ApplyResources(this.label15, "label15");
|
||||
this.label15.Name = "label15";
|
||||
//
|
||||
// label16
|
||||
//
|
||||
resources.ApplyResources(this.label16, "label16");
|
||||
this.label16.Name = "label16";
|
||||
//
|
||||
// label17
|
||||
//
|
||||
resources.ApplyResources(this.label17, "label17");
|
||||
this.label17.Name = "label17";
|
||||
//
|
||||
// label20
|
||||
//
|
||||
resources.ApplyResources(this.label20, "label20");
|
||||
this.label20.Name = "label20";
|
||||
//
|
||||
// label21
|
||||
//
|
||||
resources.ApplyResources(this.label21, "label21");
|
||||
this.label21.Name = "label21";
|
||||
//
|
||||
// label22
|
||||
//
|
||||
resources.ApplyResources(this.label22, "label22");
|
||||
this.label22.Name = "label22";
|
||||
//
|
||||
// label23
|
||||
//
|
||||
resources.ApplyResources(this.label23, "label23");
|
||||
this.label23.Name = "label23";
|
||||
//
|
||||
// label24
|
||||
//
|
||||
resources.ApplyResources(this.label24, "label24");
|
||||
this.label24.Name = "label24";
|
||||
//
|
||||
// label25
|
||||
//
|
||||
resources.ApplyResources(this.label25, "label25");
|
||||
this.label25.Name = "label25";
|
||||
//
|
||||
// label26
|
||||
//
|
||||
resources.ApplyResources(this.label26, "label26");
|
||||
this.label26.Name = "label26";
|
||||
//
|
||||
// label27
|
||||
//
|
||||
resources.ApplyResources(this.label27, "label27");
|
||||
this.label27.Name = "label27";
|
||||
//
|
||||
// label28
|
||||
//
|
||||
resources.ApplyResources(this.label28, "label28");
|
||||
this.label28.Name = "label28";
|
||||
//
|
||||
// label29
|
||||
//
|
||||
resources.ApplyResources(this.label29, "label29");
|
||||
this.label29.Name = "label29";
|
||||
//
|
||||
// label30
|
||||
//
|
||||
resources.ApplyResources(this.label30, "label30");
|
||||
this.label30.Name = "label30";
|
||||
//
|
||||
// label31
|
||||
//
|
||||
resources.ApplyResources(this.label31, "label31");
|
||||
this.label31.Name = "label31";
|
||||
//
|
||||
// label32
|
||||
//
|
||||
resources.ApplyResources(this.label32, "label32");
|
||||
this.label32.Name = "label32";
|
||||
//
|
||||
// BUT_syncS8
|
||||
//
|
||||
resources.ApplyResources(this.BUT_syncS8, "BUT_syncS8");
|
||||
this.BUT_syncS8.Name = "BUT_syncS8";
|
||||
this.BUT_syncS8.UseVisualStyleBackColor = true;
|
||||
this.BUT_syncS8.Click += new System.EventHandler(this.BUT_syncS8_Click);
|
||||
//
|
||||
// BUT_syncS9
|
||||
//
|
||||
resources.ApplyResources(this.BUT_syncS9, "BUT_syncS9");
|
||||
this.BUT_syncS9.Name = "BUT_syncS9";
|
||||
this.BUT_syncS9.UseVisualStyleBackColor = true;
|
||||
this.BUT_syncS9.Click += new System.EventHandler(this.BUT_syncS9_Click);
|
||||
//
|
||||
// BUT_syncS10
|
||||
//
|
||||
resources.ApplyResources(this.BUT_syncS10, "BUT_syncS10");
|
||||
this.BUT_syncS10.Name = "BUT_syncS10";
|
||||
this.BUT_syncS10.UseVisualStyleBackColor = true;
|
||||
this.BUT_syncS10.Click += new System.EventHandler(this.BUT_syncS10_Click);
|
||||
//
|
||||
// _3DRradio
|
||||
//
|
||||
resources.ApplyResources(this, "$this");
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.BUT_syncS10);
|
||||
this.Controls.Add(this.BUT_syncS9);
|
||||
this.Controls.Add(this.BUT_syncS8);
|
||||
this.Controls.Add(this.label25);
|
||||
this.Controls.Add(this.label26);
|
||||
this.Controls.Add(this.label27);
|
||||
this.Controls.Add(this.label28);
|
||||
this.Controls.Add(this.label29);
|
||||
this.Controls.Add(this.label30);
|
||||
this.Controls.Add(this.label31);
|
||||
this.Controls.Add(this.label32);
|
||||
this.Controls.Add(this.label20);
|
||||
this.Controls.Add(this.label21);
|
||||
this.Controls.Add(this.label22);
|
||||
this.Controls.Add(this.label23);
|
||||
this.Controls.Add(this.label24);
|
||||
this.Controls.Add(this.RS8);
|
||||
this.Controls.Add(this.RS12);
|
||||
this.Controls.Add(this.RS11);
|
||||
this.Controls.Add(this.RS10);
|
||||
this.Controls.Add(this.RS9);
|
||||
this.Controls.Add(this.label17);
|
||||
this.Controls.Add(this.label16);
|
||||
this.Controls.Add(this.label15);
|
||||
this.Controls.Add(this.label14);
|
||||
this.Controls.Add(this.label13);
|
||||
this.Controls.Add(this.S8);
|
||||
this.Controls.Add(this.S12);
|
||||
this.Controls.Add(this.S11);
|
||||
this.Controls.Add(this.S10);
|
||||
this.Controls.Add(this.S9);
|
||||
this.Controls.Add(this.BUT_syncS5);
|
||||
this.Controls.Add(this.BUT_syncS3);
|
||||
this.Controls.Add(this.BUT_syncS2);
|
||||
@ -499,7 +849,7 @@
|
||||
this.Controls.Add(this.lbl_status);
|
||||
this.Controls.Add(this.Progressbar);
|
||||
this.Controls.Add(this.BUT_upload);
|
||||
this.MinimumSize = new System.Drawing.Size(334, 482);
|
||||
this.MinimumSize = new System.Drawing.Size(781, 433);
|
||||
this.Name = "_3DRradio";
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
@ -548,5 +898,36 @@
|
||||
private MyButton BUT_syncS2;
|
||||
private MyButton BUT_syncS3;
|
||||
private MyButton BUT_syncS5;
|
||||
private System.Windows.Forms.ComboBox S9;
|
||||
private System.Windows.Forms.ComboBox S10;
|
||||
private System.Windows.Forms.ComboBox S11;
|
||||
private System.Windows.Forms.ComboBox S12;
|
||||
private System.Windows.Forms.ComboBox S8;
|
||||
private System.Windows.Forms.Label label13;
|
||||
private System.Windows.Forms.Label label14;
|
||||
private System.Windows.Forms.Label label15;
|
||||
private System.Windows.Forms.Label label16;
|
||||
private System.Windows.Forms.Label label17;
|
||||
private System.Windows.Forms.Label label20;
|
||||
private System.Windows.Forms.Label label21;
|
||||
private System.Windows.Forms.Label label22;
|
||||
private System.Windows.Forms.Label label23;
|
||||
private System.Windows.Forms.Label label24;
|
||||
private System.Windows.Forms.ComboBox RS8;
|
||||
private System.Windows.Forms.ComboBox RS12;
|
||||
private System.Windows.Forms.ComboBox RS11;
|
||||
private System.Windows.Forms.ComboBox RS10;
|
||||
private System.Windows.Forms.ComboBox RS9;
|
||||
private System.Windows.Forms.Label label25;
|
||||
private System.Windows.Forms.Label label26;
|
||||
private System.Windows.Forms.Label label27;
|
||||
private System.Windows.Forms.Label label28;
|
||||
private System.Windows.Forms.Label label29;
|
||||
private System.Windows.Forms.Label label30;
|
||||
private System.Windows.Forms.Label label31;
|
||||
private System.Windows.Forms.Label label32;
|
||||
private MyButton BUT_syncS8;
|
||||
private MyButton BUT_syncS9;
|
||||
private MyButton BUT_syncS10;
|
||||
}
|
||||
}
|
@ -14,6 +14,37 @@ namespace ArdupilotMega
|
||||
{
|
||||
public partial class _3DRradio : BackStageViewContentPanel
|
||||
{
|
||||
/*
|
||||
responce 0 S0: FORMAT=25
|
||||
|
||||
S1: SERIAL_SPEED=57
|
||||
|
||||
S2: AIR_SPEED=64
|
||||
|
||||
S3: NETID=25
|
||||
|
||||
S4: TXPOWER=20
|
||||
|
||||
S5: ECC=1
|
||||
|
||||
S6: MAVLINK=1
|
||||
|
||||
S7: OPPRESEND=1
|
||||
|
||||
S8: MIN_FREQ=915000
|
||||
|
||||
S9: MAX_FREQ=928000
|
||||
|
||||
S10: NUM_CHANNELS=50
|
||||
|
||||
S11: DUTY_CYCLE=100
|
||||
|
||||
S12: LBT_RSSI=0
|
||||
|
||||
S13: MANCHESTER=0
|
||||
|
||||
*/
|
||||
|
||||
public delegate void LogEventHandler(string message, int level = 0);
|
||||
|
||||
public delegate void ProgressEventHandler(double completed);
|
||||
@ -65,8 +96,7 @@ namespace ArdupilotMega
|
||||
|
||||
bool bootloadermode = false;
|
||||
|
||||
uploader.ProgressEvent += new ProgressEventHandler(uploader_ProgressEvent);
|
||||
uploader.LogEvent += new LogEventHandler(uploader_LogEvent);
|
||||
|
||||
|
||||
try
|
||||
{
|
||||
@ -74,6 +104,10 @@ namespace ArdupilotMega
|
||||
uploader_LogEvent("Trying Bootloader Mode");
|
||||
uploader.port = comPort;
|
||||
uploader.connect_and_sync();
|
||||
|
||||
uploader.ProgressEvent += new ProgressEventHandler(uploader_ProgressEvent);
|
||||
uploader.LogEvent += new LogEventHandler(uploader_LogEvent);
|
||||
|
||||
uploader_LogEvent("In Bootloader Mode");
|
||||
bootloadermode = true;
|
||||
}
|
||||
@ -82,12 +116,15 @@ namespace ArdupilotMega
|
||||
comPort.Close();
|
||||
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
|
||||
comPort.Open();
|
||||
|
||||
uploader.ProgressEvent += new ProgressEventHandler(uploader_ProgressEvent);
|
||||
uploader.LogEvent += new LogEventHandler(uploader_LogEvent);
|
||||
|
||||
uploader_LogEvent("Trying Firmware Mode");
|
||||
bootloadermode = false;
|
||||
}
|
||||
|
||||
|
||||
|
||||
if (bootloadermode || doConnect(comPort))
|
||||
{
|
||||
if (getFirmware())
|
||||
@ -617,5 +654,20 @@ namespace ArdupilotMega
|
||||
{
|
||||
RS5.Checked = S5.Checked;
|
||||
}
|
||||
|
||||
private void BUT_syncS8_Click(object sender, EventArgs e)
|
||||
{
|
||||
RS8.Text = S8.Text;
|
||||
}
|
||||
|
||||
private void BUT_syncS9_Click(object sender, EventArgs e)
|
||||
{
|
||||
RS9.Text = S9.Text;
|
||||
}
|
||||
|
||||
private void BUT_syncS10_Click(object sender, EventArgs e)
|
||||
{
|
||||
RS10.Text = S10.Text;
|
||||
}
|
||||
}
|
||||
}
|
File diff suppressed because it is too large
Load Diff
Binary file not shown.
@ -1 +1 @@
|
||||
1.1.4493.14496
|
||||
1.1.4494.38818
|
@ -8,3 +8,4 @@ Test Developer ...
|
||||
|
||||
Chris Anderson
|
||||
Phil Cole after following the instructions explicitly.
|
||||
Craig Elder was here.
|
||||
|
@ -102,6 +102,9 @@ protected:
|
||||
// the limit of the gyro drift claimed by the sensors, in
|
||||
// radians/s/s
|
||||
float _gyro_drift_limit;
|
||||
|
||||
// acceleration due to gravity in m/s/s
|
||||
static const float _gravity = 9.80665;
|
||||
};
|
||||
|
||||
#include <AP_AHRS_DCM.h>
|
||||
|
@ -279,7 +279,6 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
||||
Vector3f accel;
|
||||
Vector3f error;
|
||||
float error_norm = 0;
|
||||
const float gravity_squared = (9.80665*9.80665);
|
||||
float yaw_deltat = 0;
|
||||
|
||||
accel = _accel_vector;
|
||||
@ -295,59 +294,43 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
||||
|
||||
//*****Roll and Pitch***************
|
||||
|
||||
// calculate the z component of the accel vector assuming it
|
||||
// has a length of 9.8. This discards the z accelerometer
|
||||
// sensor reading completely. Logs show that the z accel is
|
||||
// the noisest, plus it has a disproportionate impact on the
|
||||
// drift correction result because of the geometry when we are
|
||||
// mostly flat. Dropping it completely seems to make the DCM
|
||||
// algorithm much more resilient to large amounts of
|
||||
// accelerometer noise.
|
||||
float zsquared = gravity_squared - ((accel.x * accel.x) + (accel.y * accel.y));
|
||||
if (zsquared < 0) {
|
||||
// normalise the accelerometer vector to a standard length
|
||||
// this is important to reduce the impact of noise on the
|
||||
// drift correction, as very noisy vectors tend to have
|
||||
// abnormally high lengths. By normalising the length we
|
||||
// reduce their impact.
|
||||
float accel_length = accel.length();
|
||||
accel *= (_gravity / accel_length);
|
||||
if (accel.is_inf()) {
|
||||
// we can't do anything useful with this sample
|
||||
_omega_P.zero();
|
||||
} else {
|
||||
if (accel.z > 0) {
|
||||
accel.z = sqrt(zsquared);
|
||||
} else {
|
||||
accel.z = -sqrt(zsquared);
|
||||
}
|
||||
|
||||
// calculate the error, in m/2^2, between the attitude
|
||||
// implied by the accelerometers and the attitude
|
||||
// in the current DCM matrix
|
||||
error = _dcm_matrix.c % accel;
|
||||
|
||||
// error from the above is in m/s^2 units.
|
||||
|
||||
// Limit max error to limit the effect of noisy values
|
||||
// on the algorithm. This limits the error to about 11
|
||||
// degrees
|
||||
error_norm = error.length();
|
||||
if (error_norm > 2) {
|
||||
error *= (2 / error_norm);
|
||||
}
|
||||
|
||||
// we now want to calculate _omega_P and _omega_I. The
|
||||
// _omega_P value is what drags us quickly to the
|
||||
// accelerometer reading.
|
||||
_omega_P = error * _kp_roll_pitch;
|
||||
|
||||
// the _omega_I is the long term accumulated gyro
|
||||
// error. This determines how much gyro drift we can
|
||||
// handle.
|
||||
Vector3f omega_I_delta = error * (_ki_roll_pitch * deltat);
|
||||
|
||||
// limit the slope of omega_I on each axis to
|
||||
// the maximum drift rate
|
||||
float drift_limit = _gyro_drift_limit * deltat;
|
||||
omega_I_delta.x = constrain(omega_I_delta.x, -drift_limit, drift_limit);
|
||||
omega_I_delta.y = constrain(omega_I_delta.y, -drift_limit, drift_limit);
|
||||
omega_I_delta.z = constrain(omega_I_delta.z, -drift_limit, drift_limit);
|
||||
|
||||
_omega_I += omega_I_delta;
|
||||
return;
|
||||
}
|
||||
|
||||
// calculate the error, in m/2^2, between the attitude
|
||||
// implied by the accelerometers and the attitude
|
||||
// in the current DCM matrix
|
||||
error = _dcm_matrix.c % accel;
|
||||
|
||||
// Limit max error to limit the effect of noisy values
|
||||
// on the algorithm. This limits the error to about 11
|
||||
// degrees
|
||||
error_norm = error.length();
|
||||
if (error_norm > 2) {
|
||||
error *= (2 / error_norm);
|
||||
}
|
||||
|
||||
// we now want to calculate _omega_P and _omega_I. The
|
||||
// _omega_P value is what drags us quickly to the
|
||||
// accelerometer reading.
|
||||
_omega_P = error * _kp_roll_pitch;
|
||||
|
||||
// the _omega_I is the long term accumulated gyro
|
||||
// error. This determines how much gyro drift we can
|
||||
// handle.
|
||||
_omega_I_sum += error * (_ki_roll_pitch * deltat);
|
||||
_omega_I_sum_time += deltat;
|
||||
|
||||
// these sums support the reporting of the DCM state via MAVLink
|
||||
_error_rp_sum += error_norm;
|
||||
_error_rp_count++;
|
||||
@ -467,17 +450,33 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
||||
// x/y drift correction is too inaccurate, and can lead to
|
||||
// incorrect builups in the x/y drift. We rely on the
|
||||
// accelerometers to get the x/y components right
|
||||
float omega_Iz_delta = error.z * (_ki_yaw * yaw_deltat);
|
||||
|
||||
// limit the slope of omega_I.z to the maximum gyro drift rate
|
||||
float drift_limit = _gyro_drift_limit * yaw_deltat;
|
||||
omega_Iz_delta = constrain(omega_Iz_delta, -drift_limit, drift_limit);
|
||||
|
||||
_omega_I.z += omega_Iz_delta;
|
||||
_omega_I_sum.z += error.z * (_ki_yaw * yaw_deltat);
|
||||
|
||||
// we keep the sum of yaw error for reporting via MAVLink.
|
||||
_error_yaw_sum += error_course;
|
||||
_error_yaw_count++;
|
||||
|
||||
if (_omega_I_sum_time > 10) {
|
||||
// every 10 seconds we apply the accumulated
|
||||
// _omega_I_sum changes to _omega_I. We do this to
|
||||
// prevent short term feedback between the P and I
|
||||
// terms of the controller. The _omega_I vector is
|
||||
// supposed to refect long term gyro drift, but with
|
||||
// high noise it can start to build up due to short
|
||||
// term interactions. By summing it over 10 seconds we
|
||||
// prevent the short term interactions and can apply
|
||||
// the slope limit more accurately
|
||||
float drift_limit = _gyro_drift_limit * _omega_I_sum_time;
|
||||
_omega_I_sum.x = constrain(_omega_I_sum.x, -drift_limit, drift_limit);
|
||||
_omega_I_sum.y = constrain(_omega_I_sum.y, -drift_limit, drift_limit);
|
||||
_omega_I_sum.z = constrain(_omega_I_sum.z, -drift_limit, drift_limit);
|
||||
|
||||
_omega_I += _omega_I_sum;
|
||||
|
||||
// zero the sum
|
||||
_omega_I_sum.zero();
|
||||
_omega_I_sum_time = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
@ -69,6 +69,8 @@ private:
|
||||
Vector3f _omega_P; // accel Omega Proportional correction
|
||||
Vector3f _omega_yaw_P; // yaw Omega Proportional correction
|
||||
Vector3f _omega_I; // Omega Integrator correction
|
||||
Vector3f _omega_I_sum; // summation vector for omegaI
|
||||
float _omega_I_sum_time;
|
||||
Vector3f _omega_integ_corr; // Partially corrected Gyro_Vector data - used for centrepetal correction
|
||||
Vector3f _omega; // Corrected Gyro_Vector data
|
||||
|
||||
|
@ -128,7 +128,11 @@ void AP_MotorsTri::output_armed()
|
||||
|
||||
// also send out to tail command (we rely on any auto pilot to have updated the rc_yaw->radio_out to the correct value)
|
||||
// note we do not save the radio_out to the motor_out array so it may not appear in the ch7out in the status screen of the mission planner
|
||||
_rc->OutputCh(AP_MOTORS_CH_TRI_YAW, _rc_yaw->radio_out);
|
||||
if( _rc_yaw->get_reverse() == true ) {
|
||||
_rc->OutputCh(AP_MOTORS_CH_TRI_YAW, _rc_yaw->radio_trim - (_rc_yaw->radio_out - _rc_yaw->radio_trim));
|
||||
}else{
|
||||
_rc->OutputCh(AP_MOTORS_CH_TRI_YAW, _rc_yaw->radio_out);
|
||||
}
|
||||
|
||||
// InstantPWM
|
||||
if( _speed_hz == AP_MOTORS_SPEED_INSTANT_PWM ) {
|
||||
|
@ -60,5 +60,6 @@ protected:
|
||||
};
|
||||
|
||||
#include "AP_OpticalFlow_ADNS3080.h"
|
||||
#include "AP_OpticalFlow_ADNS3080_APM2.h"
|
||||
|
||||
#endif
|
||||
|
@ -33,6 +33,17 @@
|
||||
|
||||
#define AP_SPI_TIMEOUT 1000
|
||||
|
||||
// We use Serial Port 2 in SPI Mode
|
||||
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
#define AP_SPI_DATAIN 50 // MISO // PB3
|
||||
#define AP_SPI_DATAOUT 51 // MOSI // PB2
|
||||
#define AP_SPI_CLOCK 52 // SCK // PB1
|
||||
#else // normal arduino SPI pins...these need to be checked
|
||||
#define AP_SPI_DATAIN 12 //MISO
|
||||
#define AP_SPI_DATAOUT 11 //MOSI
|
||||
#define AP_SPI_CLOCK 13 //SCK
|
||||
#endif
|
||||
|
||||
union NumericIntType
|
||||
{
|
||||
int intValue;
|
||||
|
@ -3,6 +3,10 @@
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
// default pin settings
|
||||
#define ADNS3080_CHIP_SELECT 34 // PC3
|
||||
#define ADNS3080_RESET 0 // reset pin is unattached by default
|
||||
|
||||
// orientations for ADNS3080 sensor
|
||||
#define AP_OPTICALFLOW_ADNS3080_PINS_FORWARD ROTATION_YAW_180
|
||||
#define AP_OPTICALFLOW_ADNS3080_PINS_FORWARD_RIGHT ROTATION_YAW_135
|
||||
@ -19,21 +23,6 @@
|
||||
// scaler - value returned when sensor is moved equivalent of 1 pixel
|
||||
#define AP_OPTICALFLOW_ADNS3080_SCALER 1.1
|
||||
|
||||
// We use Serial Port 2 in SPI Mode
|
||||
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
#define AP_SPI_DATAIN 50 // MISO // PB3
|
||||
#define AP_SPI_DATAOUT 51 // MOSI // PB2
|
||||
#define AP_SPI_CLOCK 52 // SCK // PB1
|
||||
#define ADNS3080_CHIP_SELECT 34 // PC3
|
||||
#define ADNS3080_RESET 0 // reset pin is unattached by default
|
||||
#else // normal arduino SPI pins...these need to be checked
|
||||
#define AP_SPI_DATAIN 12 //MISO
|
||||
#define AP_SPI_DATAOUT 11 //MOSI
|
||||
#define AP_SPI_CLOCK 13 //SCK
|
||||
#define ADNS3080_CHIP_SELECT 10 //SS
|
||||
#define ADNS3080_RESET 9 //RESET
|
||||
#endif
|
||||
|
||||
// ADNS3080 hardware config
|
||||
#define ADNS3080_PIXELS_X 30
|
||||
#define ADNS3080_PIXELS_Y 30
|
||||
@ -85,7 +74,6 @@
|
||||
#define ADNS3080_FRAME_RATE_MAX 6469
|
||||
#define ADNS3080_FRAME_RATE_MIN 2000
|
||||
|
||||
|
||||
class AP_OpticalFlow_ADNS3080 : public AP_OpticalFlow
|
||||
{
|
||||
private:
|
||||
|
536
libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080_APM2.cpp
Normal file
536
libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080_APM2.cpp
Normal file
@ -0,0 +1,536 @@
|
||||
/*
|
||||
AP_OpticalFlow_ADNS3080.cpp - ADNS3080 OpticalFlow Library for Ardupilot Mega
|
||||
Code by Randy Mackay. DIYDrones.com
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
External ADNS3080 OpticalFlow is connected via Serial port 2 (in SPI mode)
|
||||
TXD2 = MOSI = pin PH1
|
||||
RXD2 = MISO = pin PH0
|
||||
XCK2 = SCK = pin PH2
|
||||
Chip Select pin is PC4 (33) [PH6 (9)]
|
||||
We are using the 16 clocks per conversion timming to increase efficiency (fast)
|
||||
The sampling frequency is 400Hz (Timer2 overflow interrupt)
|
||||
So if our loop is at 50Hz, our needed sampling freq should be 100Hz, so
|
||||
we have an 4x oversampling and averaging.
|
||||
|
||||
Methods:
|
||||
Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt)
|
||||
Read() : Read latest values from OpticalFlow and store to x,y, surface_quality parameters
|
||||
|
||||
*/
|
||||
|
||||
#include "AP_OpticalFlow_ADNS3080.h"
|
||||
#include "SPI.h"
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
#else
|
||||
#include "WProgram.h"
|
||||
#endif
|
||||
|
||||
#define AP_SPI_TIMEOUT 1000
|
||||
|
||||
// We use Serial Port 2 in SPI Mode
|
||||
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
#define AP_SPI_DATAIN 15 // MISO
|
||||
#define AP_SPI_DATAOUT 14 // MOSI
|
||||
#define AP_SPI_CLOCK PJ2 // SCK
|
||||
#else // normal arduino SPI pins...these need to be checked
|
||||
# error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target.
|
||||
#endif
|
||||
|
||||
// mask for saving bit order and data mode to avoid interference with other users of the bus
|
||||
#define UCSR3C_MASK 0x07
|
||||
|
||||
// SPI3 setting for UCSR3C
|
||||
#define SPI3_MODE_SPI 0xC0 // UMSEL31 = 1, UMSEL30 = 1
|
||||
|
||||
// settings for phase and polarity bits of UCSR3C
|
||||
#define SPI3_MODE_MASK 0x03
|
||||
#define SPI3_MODE0 0x00
|
||||
#define SPI3_MODE1 0x01
|
||||
#define SPI3_MODE2 0x02
|
||||
#define SPI3_MODE3 0x03
|
||||
#define SPI3_MODE SPI3_MODE3
|
||||
|
||||
// settings for phase and polarity bits of UCSR3C
|
||||
#define SPI3_ORDER_MASK 0x04
|
||||
#define SPI3_MSBFIRST 0x00
|
||||
#define SPI3_LSBFIRST 0x04
|
||||
|
||||
#define SPI3_SPEED 0x04 // 2 megahertz?
|
||||
|
||||
#define SPI3_DELAY 20 // delay in microseconds after sending data
|
||||
|
||||
|
||||
union NumericIntType
|
||||
{
|
||||
int intValue;
|
||||
unsigned int uintValue;
|
||||
byte byteValue[2];
|
||||
};
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
AP_OpticalFlow_ADNS3080_APM2::AP_OpticalFlow_ADNS3080_APM2(int cs_pin, int reset_pin) : _cs_pin(cs_pin), _reset_pin(reset_pin)
|
||||
{
|
||||
num_pixels = ADNS3080_PIXELS_X;
|
||||
field_of_view = AP_OPTICALFLOW_ADNS3080_08_FOV;
|
||||
scaler = AP_OPTICALFLOW_ADNS3080_SCALER;
|
||||
}
|
||||
|
||||
// SPI Methods
|
||||
// *** INTERNAL FUNCTIONS ***
|
||||
unsigned char AP_OpticalFlow_ADNS3080_APM2::SPI_transfer(uint8_t data)
|
||||
{
|
||||
|
||||
/* Wait for empty transmit buffer */
|
||||
while ( !( UCSR3A & (1<<UDRE3)) );
|
||||
|
||||
/* Put data into buffer, sends the data */
|
||||
UDR3 = data;
|
||||
|
||||
/* Wait for data to be received */
|
||||
while ( !(UCSR3A & (1<<RXC3)) );
|
||||
|
||||
/* Get and return received data from buffer */
|
||||
return UDR3;
|
||||
}
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
// init - initialise sensor
|
||||
// initCommAPI parameter controls whether SPI interface is initialised (set to false if other devices are on the SPI bus and have already initialised the interface)
|
||||
bool
|
||||
AP_OpticalFlow_ADNS3080_APM2::init(bool initCommAPI)
|
||||
{
|
||||
int retry = 0;
|
||||
|
||||
pinMode(AP_SPI_DATAOUT,OUTPUT);
|
||||
pinMode(AP_SPI_DATAIN,INPUT);
|
||||
pinMode(AP_SPI_CLOCK,OUTPUT);
|
||||
pinMode(_cs_pin,OUTPUT);
|
||||
if( _reset_pin != 0)
|
||||
pinMode(ADNS3080_RESET,OUTPUT);
|
||||
|
||||
digitalWrite(_cs_pin,HIGH); // disable device (Chip select is active low)
|
||||
|
||||
// reset the device
|
||||
reset();
|
||||
|
||||
// start the SPI library:
|
||||
if( initCommAPI ) {
|
||||
// Setup Serial Port3 in SPI mode (MSPI), Mode 0, Clock: 8Mhz
|
||||
UBRR3 = 0;
|
||||
DDRJ |= (1<<PJ2); // SPI clock XCK3 (PJ2) as output. This enable SPI Master mode
|
||||
// put UART3 into SPI master mode
|
||||
UCSR3C = SPI3_MODE_SPI | SPI3_MODE;
|
||||
// Enable receiver and transmitter.
|
||||
UCSR3B = (1<<RXEN3)|(1<<TXEN3);
|
||||
// Set Baud rate
|
||||
UBRR3 = SPI3_SPEED; // SPI running at 8Mhz
|
||||
}
|
||||
|
||||
delay(10);
|
||||
|
||||
// check the sensor is functioning
|
||||
while( retry < 3 ) {
|
||||
if( read_register(ADNS3080_PRODUCT_ID) == 0x17 ) {
|
||||
return true;
|
||||
}
|
||||
retry++;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
//
|
||||
// backup_spi_settings - checks current SPI settings (clock speed, etc), sets values to what we need
|
||||
//
|
||||
void AP_OpticalFlow_ADNS3080_APM2::backup_spi_settings()
|
||||
{
|
||||
|
||||
uint8_t temp;
|
||||
|
||||
/* Wait for empty transmit buffer */
|
||||
while ( !( UCSR3A & (1<<UDRE3)) );
|
||||
|
||||
// store current spi values
|
||||
orig_spi_settings_ucsr3c = UCSR3C;
|
||||
orig_spi_settings_ubrr3 = UBRR3;
|
||||
|
||||
// decide new value for UCSR3C
|
||||
temp = (orig_spi_settings_ucsr3c & ~UCSR3C_MASK) | SPI3_MODE | SPI3_MSBFIRST;
|
||||
UCSR3C = temp;
|
||||
UBRR3 = SPI3_SPEED; // SPI running at 1Mhz
|
||||
}
|
||||
|
||||
// restore_spi_settings - restores SPI settings (clock speed, etc) to what their values were before the sensor used the bus
|
||||
void AP_OpticalFlow_ADNS3080_APM2::restore_spi_settings()
|
||||
{
|
||||
/* Wait for empty transmit buffer */
|
||||
while ( !( UCSR3A & (1<<UDRE3)) );
|
||||
|
||||
// restore UCSRC3C and UBRR3
|
||||
UCSR3C = orig_spi_settings_ucsr3c;
|
||||
UBRR3 = orig_spi_settings_ubrr3;
|
||||
}
|
||||
|
||||
// Read a register from the sensor
|
||||
byte
|
||||
AP_OpticalFlow_ADNS3080_APM2::read_register(byte address)
|
||||
{
|
||||
byte result = 0, junk = 0;
|
||||
|
||||
backup_spi_settings();
|
||||
|
||||
// take the chip select low to select the device
|
||||
digitalWrite(_cs_pin, LOW);
|
||||
|
||||
// send the device the register you want to read:
|
||||
junk = SPI_transfer(address);
|
||||
|
||||
// small delay
|
||||
delayMicroseconds(SPI3_DELAY);
|
||||
|
||||
// send a value of 0 to read the first byte returned:
|
||||
result = SPI_transfer(0x00);
|
||||
|
||||
// take the chip select high to de-select:
|
||||
digitalWrite(_cs_pin, HIGH);
|
||||
|
||||
restore_spi_settings();
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
// write a value to one of the sensor's registers
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::write_register(byte address, byte value)
|
||||
{
|
||||
byte junk = 0;
|
||||
|
||||
backup_spi_settings();
|
||||
|
||||
// take the chip select low to select the device
|
||||
digitalWrite(_cs_pin, LOW);
|
||||
|
||||
// send register address
|
||||
junk = SPI_transfer(address | 0x80 );
|
||||
|
||||
// small delay
|
||||
delayMicroseconds(SPI3_DELAY);
|
||||
|
||||
// send data
|
||||
junk = SPI_transfer(value);
|
||||
|
||||
// take the chip select high to de-select:
|
||||
digitalWrite(_cs_pin, HIGH);
|
||||
|
||||
restore_spi_settings();
|
||||
}
|
||||
|
||||
// reset sensor by holding a pin high (or is it low?) for 10us.
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::reset()
|
||||
{
|
||||
// return immediately if the reset pin is not defined
|
||||
if( _reset_pin == 0)
|
||||
return;
|
||||
|
||||
digitalWrite(_reset_pin,HIGH); // reset sensor
|
||||
delayMicroseconds(10);
|
||||
digitalWrite(_reset_pin,LOW); // return sensor to normal
|
||||
}
|
||||
|
||||
// read latest values from sensor and fill in x,y and totals
|
||||
bool
|
||||
AP_OpticalFlow_ADNS3080_APM2::update()
|
||||
{
|
||||
byte motion_reg;
|
||||
surface_quality = (unsigned int)read_register(ADNS3080_SQUAL);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
|
||||
// check for movement, update x,y values
|
||||
motion_reg = read_register(ADNS3080_MOTION);
|
||||
_overflow = ((motion_reg & 0x10) != 0); // check if we've had an overflow
|
||||
if( (motion_reg & 0x80) != 0 ) {
|
||||
raw_dx = ((char)read_register(ADNS3080_DELTA_X));
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
raw_dy = ((char)read_register(ADNS3080_DELTA_Y));
|
||||
_motion = true;
|
||||
}else{
|
||||
raw_dx = 0;
|
||||
raw_dy = 0;
|
||||
}
|
||||
|
||||
last_update = millis();
|
||||
|
||||
apply_orientation_matrix();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::disable_serial_pullup()
|
||||
{
|
||||
byte regVal = read_register(ADNS3080_EXTENDED_CONFIG);
|
||||
regVal = (regVal | ADNS3080_SERIALNPU_OFF);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
write_register(ADNS3080_EXTENDED_CONFIG, regVal);
|
||||
}
|
||||
|
||||
// get_led_always_on - returns true if LED is always on, false if only on when required
|
||||
bool
|
||||
AP_OpticalFlow_ADNS3080_APM2::get_led_always_on()
|
||||
{
|
||||
return ( (read_register(ADNS3080_CONFIGURATION_BITS) & 0x40) > 0 );
|
||||
}
|
||||
|
||||
// set_led_always_on - set parameter to true if you want LED always on, otherwise false for only when required
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::set_led_always_on( bool alwaysOn )
|
||||
{
|
||||
byte regVal = read_register(ADNS3080_CONFIGURATION_BITS);
|
||||
regVal = (regVal & 0xbf) | (alwaysOn << 6);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
write_register(ADNS3080_CONFIGURATION_BITS, regVal);
|
||||
}
|
||||
|
||||
// returns resolution (either 400 or 1600 counts per inch)
|
||||
int
|
||||
AP_OpticalFlow_ADNS3080_APM2::get_resolution()
|
||||
{
|
||||
if( (read_register(ADNS3080_CONFIGURATION_BITS) & 0x10) == 0 )
|
||||
return 400;
|
||||
else
|
||||
return 1600;
|
||||
}
|
||||
|
||||
// set parameter to 400 or 1600 counts per inch
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::set_resolution(int resolution)
|
||||
{
|
||||
byte regVal = read_register(ADNS3080_CONFIGURATION_BITS);
|
||||
|
||||
if( resolution == ADNS3080_RESOLUTION_400 ) {
|
||||
regVal &= ~0x10;
|
||||
scaler = AP_OPTICALFLOW_ADNS3080_SCALER;
|
||||
}else if( resolution == ADNS3080_RESOLUTION_1600) {
|
||||
regVal |= 0x10;
|
||||
scaler = AP_OPTICALFLOW_ADNS3080_SCALER * 4;
|
||||
}
|
||||
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
write_register(ADNS3080_CONFIGURATION_BITS, regVal);
|
||||
|
||||
// this will affect conversion factors so update them
|
||||
update_conversion_factors();
|
||||
}
|
||||
|
||||
// get_frame_rate_auto - return whether frame rate is set to "auto" or manual
|
||||
bool
|
||||
AP_OpticalFlow_ADNS3080_APM2::get_frame_rate_auto()
|
||||
{
|
||||
byte regVal = read_register(ADNS3080_EXTENDED_CONFIG);
|
||||
if( (regVal & 0x01) != 0 ) {
|
||||
return false;
|
||||
}else{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
// set_frame_rate_auto - set frame rate to auto (true) or manual (false)
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::set_frame_rate_auto(bool auto_frame_rate)
|
||||
{
|
||||
byte regVal = read_register(ADNS3080_EXTENDED_CONFIG);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
if( auto_frame_rate == true ) {
|
||||
// set specific frame period
|
||||
write_register(ADNS3080_FRAME_PERIOD_MAX_BOUND_LOWER,0xE0);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
write_register(ADNS3080_FRAME_PERIOD_MAX_BOUND_UPPER,0x1A);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
|
||||
// decide what value to update in extended config
|
||||
regVal = (regVal & ~0x01);
|
||||
}else{
|
||||
// decide what value to update in extended config
|
||||
regVal = (regVal & ~0x01) | 0x01;
|
||||
}
|
||||
write_register(ADNS3080_EXTENDED_CONFIG, regVal);
|
||||
}
|
||||
|
||||
// get frame period
|
||||
unsigned int
|
||||
AP_OpticalFlow_ADNS3080_APM2::get_frame_period()
|
||||
{
|
||||
NumericIntType aNum;
|
||||
aNum.byteValue[1] = read_register(ADNS3080_FRAME_PERIOD_UPPER);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
aNum.byteValue[0] = read_register(ADNS3080_FRAME_PERIOD_LOWER);
|
||||
return aNum.uintValue;
|
||||
}
|
||||
|
||||
// set frame period
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::set_frame_period(unsigned int period)
|
||||
{
|
||||
NumericIntType aNum;
|
||||
aNum.uintValue = period;
|
||||
|
||||
// set frame rate to manual
|
||||
set_frame_rate_auto(false);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
|
||||
// set specific frame period
|
||||
write_register(ADNS3080_FRAME_PERIOD_MAX_BOUND_LOWER,aNum.byteValue[0]);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
write_register(ADNS3080_FRAME_PERIOD_MAX_BOUND_UPPER,aNum.byteValue[1]);
|
||||
|
||||
}
|
||||
|
||||
unsigned int
|
||||
AP_OpticalFlow_ADNS3080_APM2::get_frame_rate()
|
||||
{
|
||||
unsigned long clockSpeed = ADNS3080_CLOCK_SPEED;
|
||||
unsigned int rate = clockSpeed / get_frame_period();
|
||||
return rate;
|
||||
}
|
||||
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::set_frame_rate(unsigned int rate)
|
||||
{
|
||||
unsigned long clockSpeed = ADNS3080_CLOCK_SPEED;
|
||||
unsigned int period = (unsigned int)(clockSpeed / (unsigned long)rate);
|
||||
|
||||
set_frame_period(period);
|
||||
}
|
||||
|
||||
// get_shutter_speed_auto - returns true if shutter speed is adjusted automatically, false if manual
|
||||
bool
|
||||
AP_OpticalFlow_ADNS3080_APM2::get_shutter_speed_auto()
|
||||
{
|
||||
byte regVal = read_register(ADNS3080_EXTENDED_CONFIG);
|
||||
if( (regVal & 0x02) > 0 ) {
|
||||
return false;
|
||||
}else{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
// set_shutter_speed_auto - set shutter speed to auto (true), or manual (false)
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::set_shutter_speed_auto(bool auto_shutter_speed)
|
||||
{
|
||||
byte regVal = read_register(ADNS3080_EXTENDED_CONFIG);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
if( auto_shutter_speed ) {
|
||||
// return shutter speed max to default
|
||||
write_register(ADNS3080_SHUTTER_MAX_BOUND_LOWER,0x8c);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
write_register(ADNS3080_SHUTTER_MAX_BOUND_UPPER,0x20);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
|
||||
// determine value to put into extended config
|
||||
regVal &= ~0x02;
|
||||
}else{
|
||||
// determine value to put into extended config
|
||||
regVal |= 0x02;
|
||||
}
|
||||
write_register(ADNS3080_EXTENDED_CONFIG, regVal);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
}
|
||||
|
||||
// get_shutter_speed_auto - returns true if shutter speed is adjusted automatically, false if manual
|
||||
unsigned int
|
||||
AP_OpticalFlow_ADNS3080_APM2::get_shutter_speed()
|
||||
{
|
||||
NumericIntType aNum;
|
||||
aNum.byteValue[1] = read_register(ADNS3080_SHUTTER_UPPER);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
aNum.byteValue[0] = read_register(ADNS3080_SHUTTER_LOWER);
|
||||
return aNum.uintValue;
|
||||
}
|
||||
|
||||
|
||||
// set_shutter_speed_auto - set shutter speed to auto (true), or manual (false)
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::set_shutter_speed(unsigned int shutter_speed)
|
||||
{
|
||||
NumericIntType aNum;
|
||||
aNum.uintValue = shutter_speed;
|
||||
|
||||
// set shutter speed to manual
|
||||
set_shutter_speed_auto(false);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
|
||||
// set specific shutter speed
|
||||
write_register(ADNS3080_SHUTTER_MAX_BOUND_LOWER,aNum.byteValue[0]);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
write_register(ADNS3080_SHUTTER_MAX_BOUND_UPPER,aNum.byteValue[1]);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
|
||||
// larger delay
|
||||
delay(50);
|
||||
|
||||
// need to update frame period to cause shutter value to take effect
|
||||
aNum.byteValue[1] = read_register(ADNS3080_FRAME_PERIOD_UPPER);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
aNum.byteValue[0] = read_register(ADNS3080_FRAME_PERIOD_LOWER);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
write_register(ADNS3080_FRAME_PERIOD_MAX_BOUND_LOWER,aNum.byteValue[0]);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
write_register(ADNS3080_FRAME_PERIOD_MAX_BOUND_UPPER,aNum.byteValue[1]);
|
||||
delayMicroseconds(SPI3_DELAY); // small delay
|
||||
}
|
||||
|
||||
// clear_motion - will cause the Delta_X, Delta_Y, and internal motion registers to be cleared
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::clear_motion()
|
||||
{
|
||||
write_register(ADNS3080_MOTION_CLEAR,0xFF); // writing anything to this register will clear the sensor's motion registers
|
||||
x = 0;
|
||||
y = 0;
|
||||
dx = 0;
|
||||
dy = 0;
|
||||
_motion = false;
|
||||
}
|
||||
|
||||
// get_pixel_data - captures an image from the sensor and stores it to the pixe_data array
|
||||
void
|
||||
AP_OpticalFlow_ADNS3080_APM2::print_pixel_data(Stream *serPort)
|
||||
{
|
||||
int i,j;
|
||||
bool isFirstPixel = true;
|
||||
byte regValue;
|
||||
byte pixelValue;
|
||||
|
||||
// write to frame capture register to force capture of frame
|
||||
write_register(ADNS3080_FRAME_CAPTURE,0x83);
|
||||
|
||||
// wait 3 frame periods + 10 nanoseconds for frame to be captured
|
||||
delayMicroseconds(1510); // min frame speed is 2000 frames/second so 1 frame = 500 nano seconds. so 500 x 3 + 10 = 1510
|
||||
|
||||
// display the pixel data
|
||||
for( i=0; i<ADNS3080_PIXELS_Y; i++ ) {
|
||||
for( j=0; j<ADNS3080_PIXELS_X; j++ ) {
|
||||
regValue = read_register(ADNS3080_FRAME_CAPTURE);
|
||||
if( isFirstPixel && (regValue & 0x40) == 0 ) {
|
||||
serPort->println("failed to find first pixel");
|
||||
}
|
||||
isFirstPixel = false;
|
||||
pixelValue = ( regValue << 2);
|
||||
serPort->print(pixelValue,DEC);
|
||||
if( j!= ADNS3080_PIXELS_X-1 )
|
||||
serPort->print(",");
|
||||
delayMicroseconds(SPI3_DELAY);
|
||||
}
|
||||
serPort->println();
|
||||
}
|
||||
|
||||
// hardware reset to restore sensor to normal operation
|
||||
reset();
|
||||
}
|
141
libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080_APM2.h
Normal file
141
libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080_APM2.h
Normal file
@ -0,0 +1,141 @@
|
||||
#ifndef AP_OPTICALFLOW_ADNS3080_APM2_H
|
||||
#define AP_OPTICALFLOW_ADNS3080_APM2_H
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
// default pin settings
|
||||
#define ADNS3080_CHIP_SELECT 34 // PC3
|
||||
#define ADNS3080_RESET 0 // reset pin is unattached by default
|
||||
|
||||
// orientations for ADNS3080 sensor
|
||||
#define AP_OPTICALFLOW_ADNS3080_PINS_FORWARD ROTATION_YAW_180
|
||||
#define AP_OPTICALFLOW_ADNS3080_PINS_FORWARD_RIGHT ROTATION_YAW_135
|
||||
#define AP_OPTICALFLOW_ADNS3080_PINS_RIGHT ROTATION_YAW_90
|
||||
#define AP_OPTICALFLOW_ADNS3080_PINS_BACK_RIGHT ROTATION_YAW_45
|
||||
#define AP_OPTICALFLOW_ADNS3080_PINS_BACK ROTATION_NONE
|
||||
#define AP_OPTICALFLOW_ADNS3080_PINS_BACK_LEFT ROTATION_YAW_315
|
||||
#define AP_OPTICALFLOW_ADNS3080_PINS_LEFT ROTATION_YAW_270
|
||||
#define AP_OPTICALFLOW_ADNS3080_PINS_FORWARD_LEFT ROTATION_YAW_225
|
||||
|
||||
// field of view of ADNS3080 sensor lenses
|
||||
#define AP_OPTICALFLOW_ADNS3080_08_FOV 0.202458 // 11.6 degrees
|
||||
|
||||
// scaler - value returned when sensor is moved equivalent of 1 pixel
|
||||
#define AP_OPTICALFLOW_ADNS3080_SCALER 1.1
|
||||
|
||||
// ADNS3080 hardware config
|
||||
#define ADNS3080_PIXELS_X 30
|
||||
#define ADNS3080_PIXELS_Y 30
|
||||
#define ADNS3080_CLOCK_SPEED 24000000
|
||||
|
||||
// Register Map for the ADNS3080 Optical OpticalFlow Sensor
|
||||
#define ADNS3080_PRODUCT_ID 0x00
|
||||
#define ADNS3080_REVISION_ID 0x01
|
||||
#define ADNS3080_MOTION 0x02
|
||||
#define ADNS3080_DELTA_X 0x03
|
||||
#define ADNS3080_DELTA_Y 0x04
|
||||
#define ADNS3080_SQUAL 0x05
|
||||
#define ADNS3080_PIXEL_SUM 0x06
|
||||
#define ADNS3080_MAXIMUM_PIXEL 0x07
|
||||
#define ADNS3080_CONFIGURATION_BITS 0x0a
|
||||
#define ADNS3080_EXTENDED_CONFIG 0x0b
|
||||
#define ADNS3080_DATA_OUT_LOWER 0x0c
|
||||
#define ADNS3080_DATA_OUT_UPPER 0x0d
|
||||
#define ADNS3080_SHUTTER_LOWER 0x0e
|
||||
#define ADNS3080_SHUTTER_UPPER 0x0f
|
||||
#define ADNS3080_FRAME_PERIOD_LOWER 0x10
|
||||
#define ADNS3080_FRAME_PERIOD_UPPER 0x11
|
||||
#define ADNS3080_MOTION_CLEAR 0x12
|
||||
#define ADNS3080_FRAME_CAPTURE 0x13
|
||||
#define ADNS3080_SROM_ENABLE 0x14
|
||||
#define ADNS3080_FRAME_PERIOD_MAX_BOUND_LOWER 0x19
|
||||
#define ADNS3080_FRAME_PERIOD_MAX_BOUND_UPPER 0x1a
|
||||
#define ADNS3080_FRAME_PERIOD_MIN_BOUND_LOWER 0x1b
|
||||
#define ADNS3080_FRAME_PERIOD_MIN_BOUND_UPPER 0x1c
|
||||
#define ADNS3080_SHUTTER_MAX_BOUND_LOWER 0x1e
|
||||
#define ADNS3080_SHUTTER_MAX_BOUND_UPPER 0x1e
|
||||
#define ADNS3080_SROM_ID 0x1f
|
||||
#define ADNS3080_OBSERVATION 0x3d
|
||||
#define ADNS3080_INVERSE_PRODUCT_ID 0x3f
|
||||
#define ADNS3080_PIXEL_BURST 0x40
|
||||
#define ADNS3080_MOTION_BURST 0x50
|
||||
#define ADNS3080_SROM_LOAD 0x60
|
||||
|
||||
// Configuration Bits
|
||||
#define ADNS3080_LED_MODE_ALWAYS_ON 0x00
|
||||
#define ADNS3080_LED_MODE_WHEN_REQUIRED 0x01
|
||||
|
||||
#define ADNS3080_RESOLUTION_400 400
|
||||
#define ADNS3080_RESOLUTION_1600 1600
|
||||
|
||||
// Extended Configuration bits
|
||||
#define ADNS3080_SERIALNPU_OFF 0x02
|
||||
|
||||
#define ADNS3080_FRAME_RATE_MAX 6469
|
||||
#define ADNS3080_FRAME_RATE_MIN 2000
|
||||
|
||||
|
||||
class AP_OpticalFlow_ADNS3080_APM2 : public AP_OpticalFlow
|
||||
{
|
||||
private:
|
||||
// bytes to store SPI settings
|
||||
byte orig_spi_settings_ucsr3c;
|
||||
byte orig_spi_settings_ubrr3;
|
||||
|
||||
// save and restore SPI settings
|
||||
void backup_spi_settings();
|
||||
void restore_spi_settings();
|
||||
|
||||
public:
|
||||
int _cs_pin; // pin used for chip select
|
||||
int _reset_pin; // pin used for chip reset
|
||||
bool _motion; // true if there has been motion
|
||||
bool _overflow; // true if the x or y data buffers overflowed
|
||||
|
||||
public:
|
||||
AP_OpticalFlow_ADNS3080_APM2(int cs_pin = ADNS3080_CHIP_SELECT, int reset_pin = ADNS3080_RESET);
|
||||
bool init(bool initCommAPI = true); // parameter controls whether I2C/SPI interface is initialised (set to false if other devices are on the I2C/SPI bus and have already initialised the interface)
|
||||
byte read_register(byte address);
|
||||
void write_register(byte address, byte value);
|
||||
void reset(); // reset sensor by holding a pin high (or is it low?) for 10us.
|
||||
bool update(); // read latest values from sensor and fill in x,y and totals, return true on successful read
|
||||
|
||||
// ADNS3080 specific features
|
||||
bool motion() { if( _motion ) { _motion = false; return true; }else{ return false; } } // return true if there has been motion since the last time this was called
|
||||
|
||||
void disable_serial_pullup();
|
||||
|
||||
bool get_led_always_on(); // returns true if LED is always on, false if only on when required
|
||||
void set_led_always_on( bool alwaysOn ); // set parameter to true if you want LED always on, otherwise false for only when required
|
||||
|
||||
int get_resolution(); // returns resolution (either 400 or 1600 counts per inch)
|
||||
void set_resolution(int resolution); // set parameter to 400 or 1600 counts per inch
|
||||
|
||||
bool get_frame_rate_auto(); // get_frame_rate_auto - return true if frame rate is set to "auto", false if manual
|
||||
void set_frame_rate_auto(bool auto_frame_rate); // set_frame_rate_auto(bool) - set frame rate to auto (true), or manual (false)
|
||||
|
||||
unsigned int get_frame_period(); // get_frame_period -
|
||||
void set_frame_period(unsigned int period);
|
||||
|
||||
unsigned int get_frame_rate();
|
||||
void set_frame_rate(unsigned int rate);
|
||||
|
||||
bool get_shutter_speed_auto(); // get_shutter_speed_auto - returns true if shutter speed is adjusted automatically, false if manual
|
||||
void set_shutter_speed_auto(bool auto_shutter_speed); // set_shutter_speed_auto - set shutter speed to auto (true), or manual (false)
|
||||
|
||||
unsigned int get_shutter_speed();
|
||||
void set_shutter_speed(unsigned int shutter_speed);
|
||||
|
||||
void clear_motion(); // will cause the x,y, dx, dy, and the sensor's motion registers to be cleared
|
||||
|
||||
void print_pixel_data(Stream *serPort); // dumps a 30x30 image to the Serial port
|
||||
|
||||
// SPI functions - we use UAT3 which is not supported by Arduino
|
||||
unsigned char SPI_transfer(unsigned char data);
|
||||
void CS_inactive();
|
||||
void CS_active();
|
||||
void PageErase (uint16_t PageAdr);
|
||||
void ChipErase ();
|
||||
};
|
||||
|
||||
#endif
|
@ -19,19 +19,21 @@
|
||||
//
|
||||
FastSerialPort0(Serial); // FTDI/console
|
||||
|
||||
AP_OpticalFlow_ADNS3080 flowSensor;
|
||||
//AP_OpticalFlow_ADNS3080 flowSensor(A3); // override chip select pin to use A3 if using APM2
|
||||
AP_OpticalFlow_ADNS3080 flowSensor; // for APM1
|
||||
//AP_OpticalFlow_ADNS3080_APM2 flowSensor(A3); // override chip select pin to use A3 if using APM2
|
||||
|
||||
void setup()
|
||||
{
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println("ArduPilot Mega OpticalFlow library test ver 1.5");
|
||||
|
||||
delay(1000);
|
||||
|
||||
|
||||
// flowSensor initialization
|
||||
if( flowSensor.init() == false )
|
||||
Serial.println("Failed to initialise ADNS3080");
|
||||
if( flowSensor.init(true) == false ) {
|
||||
Serial.print("Failed to initialise ADNS3080 ");
|
||||
}
|
||||
|
||||
flowSensor.set_orientation(AP_OPTICALFLOW_ADNS3080_PINS_FORWARD);
|
||||
flowSensor.set_field_of_view(AP_OPTICALFLOW_ADNS3080_08_FOV);
|
||||
|
||||
@ -336,7 +338,7 @@ void display_motion()
|
||||
void loop()
|
||||
{
|
||||
int value;
|
||||
|
||||
|
||||
// display menu to user
|
||||
display_menu();
|
||||
|
||||
|
@ -1,5 +1,6 @@
|
||||
AP_OpticalFlow KEYWORD1
|
||||
AP_OpticalFlow_ADNS3080 KEYWORD1
|
||||
AP_OpticalFlow_ADNS3080_APM2 KEYWORD1
|
||||
init KEYWORD2
|
||||
read KEYWORD2
|
||||
update KEYWORD2
|
||||
|
@ -91,14 +91,16 @@ unsigned char DataFlash_APM2::SPI_transfer(unsigned char data)
|
||||
return UDR3;
|
||||
}
|
||||
|
||||
// disable device
|
||||
void DataFlash_APM2::CS_inactive()
|
||||
{
|
||||
digitalWrite(DF_SLAVESELECT,HIGH); //disable device
|
||||
digitalWrite(DF_SLAVESELECT,HIGH);
|
||||
}
|
||||
|
||||
// enable device
|
||||
void DataFlash_APM2::CS_active()
|
||||
{
|
||||
digitalWrite(DF_SLAVESELECT,LOW); //enable device
|
||||
digitalWrite(DF_SLAVESELECT,LOW);
|
||||
}
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
@ -109,223 +111,261 @@ DataFlash_APM2::DataFlash_APM2()
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
void DataFlash_APM2::Init(void)
|
||||
{
|
||||
pinMode(DF_DATAOUT, OUTPUT);
|
||||
pinMode(DF_DATAIN, INPUT);
|
||||
pinMode(DF_SLAVESELECT,OUTPUT);
|
||||
pinMode(DF_RESET,OUTPUT);
|
||||
pinMode(DF_CARDDETECT, INPUT);
|
||||
pinMode(DF_DATAOUT, OUTPUT);
|
||||
pinMode(DF_DATAIN, INPUT);
|
||||
pinMode(DF_SLAVESELECT,OUTPUT);
|
||||
pinMode(DF_RESET,OUTPUT);
|
||||
pinMode(DF_CARDDETECT, INPUT);
|
||||
|
||||
// Reset the chip
|
||||
digitalWrite(DF_RESET,LOW);
|
||||
delay(1);
|
||||
digitalWrite(DF_RESET,HIGH);
|
||||
// Reset the chip
|
||||
digitalWrite(DF_RESET,LOW);
|
||||
delay(1);
|
||||
digitalWrite(DF_RESET,HIGH);
|
||||
|
||||
CS_inactive(); //disable device
|
||||
// disable device
|
||||
CS_inactive();
|
||||
|
||||
// Setup Serial Port3 in SPI mode (MSPI), Mode 0, Clock: 8Mhz
|
||||
UBRR3 = 0;
|
||||
DDRJ |= (1<<PJ2); // SPI clock XCK3 (PJ2) as output. This enable SPI Master mode
|
||||
// Set MSPI mode of operation and SPI data mode 0.
|
||||
UCSR3C = (1<<UMSEL31)|(1<<UMSEL30); //|(1<<1)|(1<<UCPOL3);
|
||||
// Enable receiver and transmitter.
|
||||
UCSR3B = (1<<RXEN3)|(1<<TXEN3);
|
||||
// Set Baud rate
|
||||
UBRR3 = 0; // SPI running at 8Mhz
|
||||
// Setup Serial Port3 in SPI mode (MSPI), Mode 0, Clock: 8Mhz
|
||||
UBRR3 = 0;
|
||||
DDRJ |= (1<<PJ2); // SPI clock XCK3 (PJ2) as output. This enable SPI Master mode
|
||||
// Set MSPI mode of operation and SPI data mode 0.
|
||||
UCSR3C = (1<<UMSEL31)|(1<<UMSEL30); //|(1<<1)|(1<<UCPOL3);
|
||||
// Enable receiver and transmitter.
|
||||
UCSR3B = (1<<RXEN3)|(1<<TXEN3);
|
||||
// Set Baud rate
|
||||
UBRR3 = 0; // SPI running at 8Mhz
|
||||
|
||||
// get page size: 512 or 528 (by default: 528)
|
||||
df_PageSize=PageSize();
|
||||
// get page size: 512 or 528 (by default: 528)
|
||||
df_PageSize=PageSize();
|
||||
|
||||
ReadManufacturerID();
|
||||
ReadManufacturerID();
|
||||
|
||||
// see page 22 of the spec for the density code
|
||||
uint8_t density_code = (df_device >> 8) & 0x1F;
|
||||
|
||||
// note that we set df_NumPages to one lower than the highest, as
|
||||
// the last page is reserved for a config page
|
||||
if (density_code == 0x7) {
|
||||
// 32 Mbit
|
||||
df_NumPages = 8191;
|
||||
} else if (density_code == 0x6) {
|
||||
// 16 Mbit
|
||||
df_NumPages = 4095;
|
||||
} else {
|
||||
// what is this??? card not inserted perhaps?
|
||||
df_NumPages = 0;
|
||||
}
|
||||
// see page 22 of the spec for the density code
|
||||
uint8_t density_code = (df_device >> 8) & 0x1F;
|
||||
|
||||
// note that we set df_NumPages to one lower than the highest, as
|
||||
// the last page is reserved for a config page
|
||||
if (density_code == 0x7) {
|
||||
// 32 Mbit
|
||||
df_NumPages = 8191;
|
||||
} else if (density_code == 0x6) {
|
||||
// 16 Mbit
|
||||
df_NumPages = 4095;
|
||||
} else {
|
||||
// what is this??? card not inserted perhaps?
|
||||
df_NumPages = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// This function is mainly to test the device
|
||||
void DataFlash_APM2::ReadManufacturerID()
|
||||
{
|
||||
CS_inactive(); // Reset dataflash command decoder
|
||||
CS_active();
|
||||
// activate dataflash command decoder
|
||||
CS_active();
|
||||
|
||||
// Read manufacturer and ID command...
|
||||
SPI_transfer(DF_READ_MANUFACTURER_AND_DEVICE_ID);
|
||||
// Read manufacturer and ID command...
|
||||
SPI_transfer(DF_READ_MANUFACTURER_AND_DEVICE_ID);
|
||||
|
||||
df_manufacturer = SPI_transfer(0xff);
|
||||
df_device = SPI_transfer(0xff);
|
||||
df_device = (df_device<<8) | SPI_transfer(0xff);
|
||||
SPI_transfer(0xff);
|
||||
df_manufacturer = SPI_transfer(0xff);
|
||||
df_device = SPI_transfer(0xff);
|
||||
df_device = (df_device<<8) | SPI_transfer(0xff);
|
||||
SPI_transfer(0xff);
|
||||
|
||||
// release SPI bus for use by other sensors
|
||||
CS_inactive();
|
||||
}
|
||||
|
||||
// This function return 1 if Card is inserted on SD slot
|
||||
bool DataFlash_APM2::CardInserted()
|
||||
{
|
||||
return (df_NumPages >= 4095 && digitalRead(DF_CARDDETECT) == 0);
|
||||
return (df_NumPages >= 4095 && digitalRead(DF_CARDDETECT) == 0);
|
||||
}
|
||||
|
||||
// Read the status register
|
||||
byte DataFlash_APM2::ReadStatusReg()
|
||||
{
|
||||
CS_inactive(); // Reset dataflash command decoder
|
||||
CS_active();
|
||||
byte tmp;
|
||||
|
||||
// Read status command
|
||||
SPI_transfer(DF_STATUS_REGISTER_READ);
|
||||
return SPI_transfer(0x00); // We only want to extract the READY/BUSY bit
|
||||
// activate dataflash command decoder
|
||||
CS_active();
|
||||
|
||||
// Read status command
|
||||
SPI_transfer(DF_STATUS_REGISTER_READ);
|
||||
tmp = SPI_transfer(0x00); // We only want to extract the READY/BUSY bit
|
||||
|
||||
// release SPI bus for use by other sensors
|
||||
CS_inactive();
|
||||
|
||||
return tmp;
|
||||
}
|
||||
|
||||
// Read the status of the DataFlash
|
||||
inline
|
||||
byte DataFlash_APM2::ReadStatus()
|
||||
{
|
||||
return(ReadStatusReg()&0x80); // We only want to extract the READY/BUSY bit
|
||||
return(ReadStatusReg()&0x80); // We only want to extract the READY/BUSY bit
|
||||
}
|
||||
|
||||
|
||||
inline
|
||||
uint16_t DataFlash_APM2::PageSize()
|
||||
{
|
||||
return(528-((ReadStatusReg()&0x01)<<4)); // if first bit 1 trhen 512 else 528 bytes
|
||||
return(528-((ReadStatusReg()&0x01)<<4)); // if first bit 1 trhen 512 else 528 bytes
|
||||
}
|
||||
|
||||
|
||||
// Wait until DataFlash is in ready state...
|
||||
void DataFlash_APM2::WaitReady()
|
||||
{
|
||||
while(!ReadStatus());
|
||||
while(!ReadStatus());
|
||||
}
|
||||
|
||||
void DataFlash_APM2::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
||||
{
|
||||
CS_inactive();
|
||||
CS_active();
|
||||
if (BufferNum==1)
|
||||
SPI_transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
|
||||
else
|
||||
SPI_transfer(DF_TRANSFER_PAGE_TO_BUFFER_2);
|
||||
// activate dataflash command decoder
|
||||
CS_active();
|
||||
|
||||
if(df_PageSize==512){
|
||||
SPI_transfer((unsigned char)(PageAdr >> 7));
|
||||
SPI_transfer((unsigned char)(PageAdr << 1));
|
||||
}else{
|
||||
SPI_transfer((unsigned char)(PageAdr >> 6));
|
||||
SPI_transfer((unsigned char)(PageAdr << 2));
|
||||
}
|
||||
SPI_transfer(0x00); // don´t care bytes
|
||||
if (BufferNum==1)
|
||||
SPI_transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
|
||||
else
|
||||
SPI_transfer(DF_TRANSFER_PAGE_TO_BUFFER_2);
|
||||
|
||||
CS_inactive(); //initiate the transfer
|
||||
CS_active();
|
||||
if(df_PageSize==512){
|
||||
SPI_transfer((unsigned char)(PageAdr >> 7));
|
||||
SPI_transfer((unsigned char)(PageAdr << 1));
|
||||
}else{
|
||||
SPI_transfer((unsigned char)(PageAdr >> 6));
|
||||
SPI_transfer((unsigned char)(PageAdr << 2));
|
||||
}
|
||||
SPI_transfer(0x00); // don´t care bytes
|
||||
|
||||
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
|
||||
//initiate the transfer
|
||||
CS_inactive();
|
||||
CS_active();
|
||||
|
||||
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
|
||||
|
||||
// release SPI bus for use by other sensors
|
||||
CS_inactive();
|
||||
}
|
||||
|
||||
void DataFlash_APM2::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
|
||||
{
|
||||
CS_inactive(); // Reset dataflash command decoder
|
||||
CS_active();
|
||||
// activate dataflash command decoder
|
||||
CS_active();
|
||||
|
||||
if (BufferNum==1)
|
||||
SPI_transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
|
||||
else
|
||||
SPI_transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE);
|
||||
if (BufferNum==1)
|
||||
SPI_transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
|
||||
else
|
||||
SPI_transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE);
|
||||
|
||||
if(df_PageSize==512){
|
||||
SPI_transfer((unsigned char)(PageAdr >> 7));
|
||||
SPI_transfer((unsigned char)(PageAdr << 1));
|
||||
}else{
|
||||
SPI_transfer((unsigned char)(PageAdr >> 6));
|
||||
SPI_transfer((unsigned char)(PageAdr << 2));
|
||||
}
|
||||
SPI_transfer(0x00); // don´t care bytes
|
||||
if(df_PageSize==512){
|
||||
SPI_transfer((unsigned char)(PageAdr >> 7));
|
||||
SPI_transfer((unsigned char)(PageAdr << 1));
|
||||
}else{
|
||||
SPI_transfer((unsigned char)(PageAdr >> 6));
|
||||
SPI_transfer((unsigned char)(PageAdr << 2));
|
||||
}
|
||||
SPI_transfer(0x00); // don´t care bytes
|
||||
|
||||
CS_inactive(); //initiate the transfer
|
||||
CS_active();
|
||||
//initiate the transfer
|
||||
CS_inactive();
|
||||
CS_active();
|
||||
|
||||
// Check if we need to wait to write the buffer to memory or we can continue...
|
||||
if (wait)
|
||||
// Check if we need to wait to write the buffer to memory or we can continue...
|
||||
if (wait)
|
||||
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
|
||||
|
||||
// release SPI bus for use by other sensors
|
||||
CS_inactive();
|
||||
}
|
||||
|
||||
void DataFlash_APM2::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
|
||||
{
|
||||
CS_inactive(); // Reset dataflash command decoder
|
||||
CS_active();
|
||||
// activate dataflash command decoder
|
||||
CS_active();
|
||||
|
||||
if (BufferNum==1)
|
||||
SPI_transfer(DF_BUFFER_1_WRITE);
|
||||
else
|
||||
SPI_transfer(DF_BUFFER_2_WRITE);
|
||||
SPI_transfer(0x00); //don't cares
|
||||
SPI_transfer((unsigned char)(IntPageAdr>>8)); //upper part of internal buffer address
|
||||
SPI_transfer((unsigned char)(IntPageAdr)); //lower part of internal buffer address
|
||||
SPI_transfer(Data); //write data byte
|
||||
if (BufferNum==1)
|
||||
SPI_transfer(DF_BUFFER_1_WRITE);
|
||||
else
|
||||
SPI_transfer(DF_BUFFER_2_WRITE);
|
||||
|
||||
SPI_transfer(0x00); // don't care
|
||||
SPI_transfer((unsigned char)(IntPageAdr>>8)); // upper part of internal buffer address
|
||||
SPI_transfer((unsigned char)(IntPageAdr)); // lower part of internal buffer address
|
||||
SPI_transfer(Data); // write data byte
|
||||
|
||||
// release SPI bus for use by other sensors
|
||||
CS_inactive();
|
||||
}
|
||||
|
||||
unsigned char DataFlash_APM2::BufferRead (unsigned char BufferNum, uint16_t IntPageAdr)
|
||||
{
|
||||
byte tmp;
|
||||
byte tmp;
|
||||
|
||||
CS_inactive(); // Reset dataflash command decoder
|
||||
CS_active();
|
||||
// activate dataflash command decoder
|
||||
CS_active();
|
||||
|
||||
if (BufferNum==1)
|
||||
SPI_transfer(DF_BUFFER_1_READ);
|
||||
else
|
||||
SPI_transfer(DF_BUFFER_2_READ);
|
||||
SPI_transfer(0x00); //don't cares
|
||||
SPI_transfer((unsigned char)(IntPageAdr>>8)); //upper part of internal buffer address
|
||||
SPI_transfer((unsigned char)(IntPageAdr)); //lower part of internal buffer address
|
||||
SPI_transfer(0x00); //don't cares
|
||||
tmp = SPI_transfer(0x00); //read data byte
|
||||
if (BufferNum==1)
|
||||
SPI_transfer(DF_BUFFER_1_READ);
|
||||
else
|
||||
SPI_transfer(DF_BUFFER_2_READ);
|
||||
|
||||
return (tmp);
|
||||
SPI_transfer(0x00);
|
||||
SPI_transfer((unsigned char)(IntPageAdr>>8)); //upper part of internal buffer address
|
||||
SPI_transfer((unsigned char)(IntPageAdr)); //lower part of internal buffer address
|
||||
SPI_transfer(0x00); //don't cares
|
||||
tmp = SPI_transfer(0x00); //read data byte
|
||||
|
||||
// release SPI bus for use by other sensors
|
||||
CS_inactive();
|
||||
|
||||
return (tmp);
|
||||
}
|
||||
// *** END OF INTERNAL FUNCTIONS ***
|
||||
|
||||
void DataFlash_APM2::PageErase (uint16_t PageAdr)
|
||||
{
|
||||
CS_inactive(); //make sure to toggle CS signal in order
|
||||
CS_active(); //to reset Dataflash command decoder
|
||||
SPI_transfer(DF_PAGE_ERASE); // Command
|
||||
// activate dataflash command decoder
|
||||
CS_active();
|
||||
|
||||
if(df_PageSize==512){
|
||||
SPI_transfer((unsigned char)(PageAdr >> 7));
|
||||
SPI_transfer((unsigned char)(PageAdr << 1));
|
||||
}else{
|
||||
SPI_transfer((unsigned char)(PageAdr >> 6));
|
||||
SPI_transfer((unsigned char)(PageAdr << 2));
|
||||
}
|
||||
// Send page erase command
|
||||
SPI_transfer(DF_PAGE_ERASE);
|
||||
|
||||
SPI_transfer(0x00); // "dont cares"
|
||||
CS_inactive(); //initiate flash page erase
|
||||
CS_active();
|
||||
while(!ReadStatus());
|
||||
if(df_PageSize==512){
|
||||
SPI_transfer((unsigned char)(PageAdr >> 7));
|
||||
SPI_transfer((unsigned char)(PageAdr << 1));
|
||||
}else{
|
||||
SPI_transfer((unsigned char)(PageAdr >> 6));
|
||||
SPI_transfer((unsigned char)(PageAdr << 2));
|
||||
}
|
||||
|
||||
SPI_transfer(0x00);
|
||||
|
||||
//initiate flash page erase
|
||||
CS_inactive();
|
||||
CS_active();
|
||||
while(!ReadStatus());
|
||||
|
||||
// release SPI bus for use by other sensors
|
||||
CS_inactive();
|
||||
}
|
||||
|
||||
|
||||
void DataFlash_APM2::ChipErase ()
|
||||
{
|
||||
CS_inactive(); //make sure to toggle CS signal in order
|
||||
CS_active(); //to reset Dataflash command decoder
|
||||
// opcodes for chip erase
|
||||
SPI_transfer(DF_CHIP_ERASE_0);
|
||||
SPI_transfer(DF_CHIP_ERASE_1);
|
||||
SPI_transfer(DF_CHIP_ERASE_2);
|
||||
SPI_transfer(DF_CHIP_ERASE_3);
|
||||
// activate dataflash command decoder
|
||||
CS_active();
|
||||
|
||||
CS_inactive(); //initiate flash page erase
|
||||
CS_active();
|
||||
while(!ReadStatus());
|
||||
}
|
||||
// opcodes for chip erase
|
||||
SPI_transfer(DF_CHIP_ERASE_0);
|
||||
SPI_transfer(DF_CHIP_ERASE_1);
|
||||
SPI_transfer(DF_CHIP_ERASE_2);
|
||||
SPI_transfer(DF_CHIP_ERASE_3);
|
||||
|
||||
//initiate flash page erase
|
||||
CS_inactive();
|
||||
CS_active();
|
||||
while(!ReadStatus());
|
||||
|
||||
// release SPI bus for use by other sensors
|
||||
CS_inactive();
|
||||
}
|
Loading…
Reference in New Issue
Block a user