APM Planner 1.1.27
fix heli setup screen force update check on start fix battery capacity
This commit is contained in:
parent
25529dec69
commit
884b08f47f
@ -328,6 +328,10 @@ namespace ArdupilotMega.GCSViews
|
|||||||
cell.Style.BackColor = Color.LightGreen;
|
cell.Style.BackColor = Color.LightGreen;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
cell.Value = 100 ;
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
cell.DataGridView.EndEdit();
|
cell.DataGridView.EndEdit();
|
||||||
|
@ -52,7 +52,7 @@
|
|||||||
resources.ApplyResources(this.BUT_updatecheck, "BUT_updatecheck");
|
resources.ApplyResources(this.BUT_updatecheck, "BUT_updatecheck");
|
||||||
this.BUT_updatecheck.Name = "BUT_updatecheck";
|
this.BUT_updatecheck.Name = "BUT_updatecheck";
|
||||||
this.BUT_updatecheck.UseVisualStyleBackColor = true;
|
this.BUT_updatecheck.UseVisualStyleBackColor = true;
|
||||||
this.BUT_updatecheck.Click += new System.EventHandler(this.BUT_updatecheck_Click);
|
this.BUT_updatecheck.Click += new System.EventHandler(Help.BUT_updatecheck_Click);
|
||||||
//
|
//
|
||||||
// Help
|
// Help
|
||||||
//
|
//
|
||||||
|
@ -22,7 +22,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
catch { }
|
catch { }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void BUT_updatecheck_Click(object sender, EventArgs e)
|
public static void BUT_updatecheck_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
Form loading = new Form();
|
Form loading = new Form();
|
||||||
loading.Width = 400;
|
loading.Width = 400;
|
||||||
|
@ -897,9 +897,51 @@ namespace ArdupilotMega.GCSViews
|
|||||||
att.roll = (aeroin.Model_fRoll * -1);
|
att.roll = (aeroin.Model_fRoll * -1);
|
||||||
att.yaw = (float)((aeroin.Model_fHeading));
|
att.yaw = (float)((aeroin.Model_fHeading));
|
||||||
|
|
||||||
att.pitchspeed = (float)-aeroin.Model_fAngVelX;
|
//Console.WriteLine("degs r {0:0.000} p {1:0.000} y {2:0.000} rates {3:0.000} {4:0.000} {5:0.000}", att.roll * -rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelZ * rad2deg);
|
||||||
att.rollspeed = (float)-aeroin.Model_fAngVelY;
|
|
||||||
att.yawspeed = (float)-aeroin.Model_fAngVelZ;
|
//Console.WriteLine("mine2 {0} {1} {2} ", answer.Item1 , answer.Item2 , answer.Item3 );
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
var answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * -rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelZ * rad2deg);
|
||||||
|
Console.WriteLine("\n{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||||
|
|
||||||
|
//answer = HIL.Utils.OGLtoBCBF(aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelZ * rad2deg, att.pitch * rad2deg, att.roll * rad2deg, att.yaw * rad2deg);
|
||||||
|
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||||
|
|
||||||
|
// answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelZ * rad2deg);
|
||||||
|
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||||
|
|
||||||
|
// answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelZ * rad2deg, aeroin.Model_fAngVelY * rad2deg);
|
||||||
|
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||||
|
|
||||||
|
// answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelZ * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelX * rad2deg);
|
||||||
|
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||||
|
|
||||||
|
// answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelZ * rad2deg, aeroin.Model_fAngVelX * rad2deg);
|
||||||
|
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||||
|
|
||||||
|
//answer = HIL.Utils.EarthRatesToBodyRatesRyan(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelZ * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelY * rad2deg);
|
||||||
|
//Console.WriteLine("{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
|
||||||
|
|
||||||
|
|
||||||
|
//att.pitchspeed = (float)answer.Item1 * deg2rad;
|
||||||
|
//att.rollspeed = (float)answer.Item2 * deg2rad;
|
||||||
|
//att.yawspeed = (float)answer.Item3 * deg2rad;
|
||||||
|
|
||||||
|
//att.pitchspeed = (float)(Math.Cos(att.yaw) * aeroin.Model_fAngVelX - Math.Sin(att.yaw) * aeroin.Model_fAngVelY);
|
||||||
|
//att.rollspeed = (float)(Math.Sin(att.yaw) * aeroin.Model_fAngVelX + Math.Cos(att.yaw) * aeroin.Model_fAngVelY);
|
||||||
|
// att.yawspeed = (float)-aeroin.Model_fAngVelZ * deg2rad;
|
||||||
|
|
||||||
|
// if (aeroin.Model_fAngVelX > 2 || aeroin.Model_fAngVelZ < -2 || aeroin.Model_fAngVelY > 2 || aeroin.Model_fAngVelY < -2)
|
||||||
|
// Console.Write("head {0:0.000}\troll {1:0.000}\tx {2:0.000} \ty {3:0.000} x2 {4:0.000} y2 {5:0.000} \n", aeroin.Model_fHeading * rad2deg, att.roll * rad2deg, aeroin.Model_fAngVelX, aeroin.Model_fAngVelY, att.pitchspeed, att.rollspeed);
|
||||||
|
|
||||||
|
|
||||||
|
//att.pitchspeed = 0;
|
||||||
|
//att.rollspeed = 0;
|
||||||
|
// att.pitchspeed = (float)answer.Item1 * deg2rad;
|
||||||
|
// att.rollspeed = (float)answer.Item2 * deg2rad;
|
||||||
|
//att.yawspeed = (float)answer.Item3 * -deg2rad;
|
||||||
|
|
||||||
|
|
||||||
#if MAVLINK10
|
#if MAVLINK10
|
||||||
@ -1334,7 +1376,10 @@ namespace ArdupilotMega.GCSViews
|
|||||||
rudder_out = (float)MainV2.cs.hilch4 / ruddergain;
|
rudder_out = (float)MainV2.cs.hilch4 / ruddergain;
|
||||||
|
|
||||||
if (RAD_aerosimrc.Checked && CHK_quad.Checked)
|
if (RAD_aerosimrc.Checked && CHK_quad.Checked)
|
||||||
throttle_out = (float)(MainV2.cs.hilch3 - 1100) / throttlegain;
|
{
|
||||||
|
throttle_out = ((float)MainV2.cs.hilch7 / 2 + 5000) / throttlegain;
|
||||||
|
//throttle_out = (float)(MainV2.cs.hilch7 - 1100) / throttlegain;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -1425,6 +1470,26 @@ namespace ArdupilotMega.GCSViews
|
|||||||
Array.Copy(BitConverter.GetBytes((double)(collective_out)), 0, AeroSimRC, 24, 8);
|
Array.Copy(BitConverter.GetBytes((double)(collective_out)), 0, AeroSimRC, 24, 8);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (CHK_quad.Checked && false)
|
||||||
|
{
|
||||||
|
//MainV2.cs.ch1out = 1100;
|
||||||
|
//MainV2.cs.ch2out = 1100;
|
||||||
|
//MainV2.cs.ch3out = 1100;
|
||||||
|
//MainV2.cs.ch4out = 1100;
|
||||||
|
|
||||||
|
//ac
|
||||||
|
// 3 front
|
||||||
|
// 1 left
|
||||||
|
// 4 back
|
||||||
|
// 2 left
|
||||||
|
|
||||||
|
Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch3out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 0, 8); // motor 1 = front
|
||||||
|
Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch1out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 8, 8); // motor 2 = right
|
||||||
|
Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch4out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 16, 8);// motor 3 = back
|
||||||
|
Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch2out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 24, 8);// motor 4 = left
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
SimulatorRECV.SendTo(AeroSimRC, Remote);
|
SimulatorRECV.SendTo(AeroSimRC, Remote);
|
||||||
|
@ -402,7 +402,7 @@ namespace ArdupilotMega.HIL
|
|||||||
return v;
|
return v;
|
||||||
}
|
}
|
||||||
|
|
||||||
static Quaternion new_rotate_euler(double heading, double attitude, double bank)
|
public static Quaternion new_rotate_euler(double heading, double attitude, double bank)
|
||||||
{
|
{
|
||||||
Quaternion Q = new Quaternion();
|
Quaternion Q = new Quaternion();
|
||||||
double c1 = Math.Cos(heading / 2);
|
double c1 = Math.Cos(heading / 2);
|
||||||
|
@ -24,7 +24,7 @@ namespace ArdupilotMega.HIL
|
|||||||
{
|
{
|
||||||
return val * deg2rad;
|
return val * deg2rad;
|
||||||
}
|
}
|
||||||
public static double degrees(double val)
|
public static double degrees(double val)
|
||||||
{
|
{
|
||||||
return val * rad2deg;
|
return val * rad2deg;
|
||||||
}
|
}
|
||||||
@ -53,52 +53,150 @@ namespace ArdupilotMega.HIL
|
|||||||
return System.Math.Tan(val);
|
return System.Math.Tan(val);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
public static Tuple<double,double,double> EarthRatesToBodyRates(double roll,double pitch,double yaw,
|
|
||||||
double rollRate,double pitchRate,double yawRate) {
|
|
||||||
//convert the angular velocities from earth frame to
|
|
||||||
//body frame. Thanks to James Goppert for the formula
|
|
||||||
|
|
||||||
//all inputs and outputs are in degrees
|
public static Tuple<double, double, double> EarthRatesToBodyRates(double roll, double pitch, double yaw,
|
||||||
|
double rollRate, double pitchRate, double yawRate)
|
||||||
|
{
|
||||||
|
//convert the angular velocities from earth frame to
|
||||||
|
//body frame. Thanks to James Goppert for the formula
|
||||||
|
|
||||||
//returns a tuple, (p,q,r)
|
//all inputs and outputs are in degrees
|
||||||
|
|
||||||
|
|
||||||
var phi = radians(roll);
|
//returns a tuple, (p,q,r)
|
||||||
var theta = radians(pitch);
|
|
||||||
var phiDot = radians(rollRate);
|
|
||||||
var thetaDot = radians(pitchRate);
|
|
||||||
var psiDot = radians(yawRate);
|
|
||||||
|
|
||||||
var p = phiDot - psiDot*sin(theta);
|
|
||||||
var q = cos(phi)*thetaDot + sin(phi)*psiDot*cos(theta);
|
|
||||||
var r = cos(phi)*psiDot*cos(theta) - sin(phi)*thetaDot;
|
|
||||||
|
|
||||||
return new Tuple<double,double,double> (degrees(p), degrees(q), degrees(r));
|
var phi = radians(roll);
|
||||||
}
|
var theta = radians(pitch);
|
||||||
|
var phiDot = radians(rollRate);
|
||||||
|
var thetaDot = radians(pitchRate);
|
||||||
|
var psiDot = radians(yawRate);
|
||||||
|
|
||||||
public static Tuple<double,double,double> BodyRatesToEarthRates(double roll, double pitch, double yaw,double pDeg, double qDeg,double rDeg){
|
var p = phiDot - psiDot * sin(theta);
|
||||||
//convert the angular velocities from body frame to
|
var q = cos(phi) * thetaDot + sin(phi) * psiDot * cos(theta);
|
||||||
//earth frame.
|
var r = cos(phi) * psiDot * cos(theta) - sin(phi) * thetaDot;
|
||||||
|
|
||||||
//all inputs and outputs are in degrees
|
return new Tuple<double, double, double>(degrees(p), degrees(q), degrees(r));
|
||||||
|
}
|
||||||
|
|
||||||
//returns a tuple, (rollRate,pitchRate,yawRate)
|
public static Tuple<double, double, double> EarthRatesToBodyRatesRyan(double roll, double pitch, double yaw,
|
||||||
|
double rollRate, double pitchRate, double yawRate)
|
||||||
|
{
|
||||||
|
// thanks to ryan beall
|
||||||
|
|
||||||
var p = radians(pDeg);
|
var phi = radians(roll);
|
||||||
var q = radians(qDeg);
|
var theta = radians(pitch);
|
||||||
var r = radians(rDeg);
|
var psi = radians(yaw);
|
||||||
|
var Po = radians(pitchRate);
|
||||||
|
var Ro = radians(yawRate);
|
||||||
|
var Qo = radians(rollRate);
|
||||||
|
|
||||||
var phi = radians(roll);
|
// CpCy, CpSy, -Sp | local_ax
|
||||||
var theta = radians(pitch);
|
// SrSpCy-CrSy, SrSpSy+CrCy, SrCp | local_ay
|
||||||
|
// CrSpCy+SrSy, CrSpSy-SrCy, CrCp | local_az
|
||||||
|
|
||||||
var phiDot = p + tan(theta)*(q*sin(phi) + r*cos(phi));
|
var P = Po * cos(psi) * cos(theta) - Ro * sin(theta) + Qo * cos(theta) * sin(psi);
|
||||||
var thetaDot = q*cos(phi) - r*sin(phi);
|
|
||||||
if (fabs(cos(theta)) < 1.0e-20)
|
|
||||||
theta += 1.0e-10;
|
|
||||||
var psiDot = (q*sin(phi) + r*cos(phi))/cos(theta);
|
|
||||||
|
|
||||||
return new Tuple<double,double,double> (degrees(phiDot), degrees(thetaDot), degrees(psiDot));
|
var Q = Qo * (cos(phi) * cos(psi) + sin(phi) * sin(psi) * sin(theta)) - Po * (cos(phi) * sin(psi) - cos(psi) * sin(phi) * sin(theta)) + Ro * cos(theta) * sin(phi);
|
||||||
|
|
||||||
|
var R = Po * (sin(phi) * sin(psi) + cos(phi) * cos(psi) * sin(theta)) - Qo * (cos(psi) * sin(phi) - cos(phi) * sin(psi) * sin(theta)) + Ro * cos(phi) * cos(theta);
|
||||||
|
|
||||||
|
return new Tuple<double, double, double>(degrees(P), degrees(Q), degrees(R));
|
||||||
|
}
|
||||||
|
|
||||||
|
public static Tuple<double, double, double> OGLtoBCBF(double phi, double theta, double psi,double x, double y, double z)
|
||||||
|
{
|
||||||
|
double x_NED, y_NED, z_NED;
|
||||||
|
double Cr, Cp, Cy;
|
||||||
|
double Sr, Sp, Sy;
|
||||||
|
|
||||||
|
//Accelerations in X-Plane are expressed in the local OpenGL reference frame, for whatever reason.
|
||||||
|
//This coordinate system is defined as follows (taken from the X-Plane SDK Wiki):
|
||||||
|
|
||||||
|
// The origin 0,0,0 is on the surface of the earth at sea level at some "reference point".
|
||||||
|
// The +X axis points east from the reference point.
|
||||||
|
// The +Z axis points south from the reference point.
|
||||||
|
// The +Y axis points straight up away from the center of the earth at the reference point.
|
||||||
|
|
||||||
|
// First we shall convert from this East Up South frame, to a more conventional NED (North East Down) frame.
|
||||||
|
x_NED = radians(x) * -1.0;
|
||||||
|
y_NED = radians(y) * 1.0;
|
||||||
|
z_NED = radians(z) * -1.0;
|
||||||
|
|
||||||
|
// Next calculate cos & sin of angles for use in the transformation matrix.
|
||||||
|
// r, p & y subscripts stand for roll pitch and yaw.
|
||||||
|
|
||||||
|
Cr = Math.Cos(radians(phi));
|
||||||
|
Cp = Math.Cos(radians(theta));
|
||||||
|
Cy = Math.Cos(radians(psi));
|
||||||
|
Sr = Math.Sin(radians(phi));
|
||||||
|
Sp = Math.Sin(radians(theta));
|
||||||
|
Sy = Math.Sin(radians(psi));
|
||||||
|
|
||||||
|
// Next we need to rotate our accelerations from the NED reference frame, into the body fixed reference frame
|
||||||
|
|
||||||
|
// THANKS TO GEORGE M SIOURIS WHOSE "MISSILE GUIDANCE AND CONTROL SYSTEMS" BOOK SEEMS TO BE THE ONLY EASY TO FIND REFERENCE THAT
|
||||||
|
// ACTUALLY GETS THE NED TO BODY FRAME ROTATION MATRIX CORRECT!!
|
||||||
|
|
||||||
|
// CpCy, CpSy, -Sp | local_ax
|
||||||
|
// SrSpCy-CrSy, SrSpSy+CrCy, SrCp | local_ay
|
||||||
|
// CrSpCy+SrSy, CrSpSy-SrCy, CrCp | local_az
|
||||||
|
|
||||||
|
x = (x_NED * Cp * Cy) + (y_NED * Cp * Sy) - (z_NED * Sp);
|
||||||
|
y = (x_NED * ((Sr * Sp * Cy) - (Cr * Sy))) + (y_NED * ((Sr * Sp * Sy) + (Cr * Cy))) + (z_NED * Sr * Cp);
|
||||||
|
z = (x_NED * ((Cr * Sp * Cy) + (Sr * Sy))) + (y_NED * ((Cr * Sp * Sy) - (Sr * Cy))) + (z_NED * Cr * Cp);
|
||||||
|
|
||||||
|
return new Tuple<double, double, double>(degrees(x), degrees(y), degrees(z));
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// From http://code.google.com/p/gentlenav/source/browse/trunk/Tools/XP_UDB_HILSIM/utility.cpp
|
||||||
|
/// Converts from xplanes to fixed body ref
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="x"></param>
|
||||||
|
/// <param name="y"></param>
|
||||||
|
/// <param name="z"></param>
|
||||||
|
/// <param name="alpha"></param>
|
||||||
|
/// <param name="beta"></param>
|
||||||
|
public static void FLIGHTtoBCBF(ref float x, ref float y, ref float z, float alpha, float beta)
|
||||||
|
{
|
||||||
|
float Ca = (float)Math.Cos(alpha);
|
||||||
|
float Cb = (float)Math.Cos(beta);
|
||||||
|
float Sa = (float)Math.Sin(alpha);
|
||||||
|
float Sb = (float)Math.Sin(beta);
|
||||||
|
|
||||||
|
float X_plane = (x * Ca * Cb) - (z * Sa * Cb) - (y * Sb);
|
||||||
|
float Y_plane = (z * Sa * Sb) - (x * Ca * Sb) - (y * Cb);
|
||||||
|
float Z_plane = (x * Sa) + (z * Ca);
|
||||||
|
|
||||||
|
x = X_plane;
|
||||||
|
y = Y_plane;
|
||||||
|
z = Z_plane;
|
||||||
|
}
|
||||||
|
|
||||||
|
public static Tuple<double, double, double> BodyRatesToEarthRates(double roll, double pitch, double yaw, double pDeg, double qDeg, double rDeg)
|
||||||
|
{
|
||||||
|
//convert the angular velocities from body frame to
|
||||||
|
//earth frame.
|
||||||
|
|
||||||
|
//all inputs and outputs are in degrees
|
||||||
|
|
||||||
|
//returns a tuple, (rollRate,pitchRate,yawRate)
|
||||||
|
|
||||||
|
var p = radians(pDeg);
|
||||||
|
var q = radians(qDeg);
|
||||||
|
var r = radians(rDeg);
|
||||||
|
|
||||||
|
var phi = radians(roll);
|
||||||
|
var theta = radians(pitch);
|
||||||
|
|
||||||
|
var phiDot = p + tan(theta) * (q * sin(phi) + r * cos(phi));
|
||||||
|
var thetaDot = q * cos(phi) - r * sin(phi);
|
||||||
|
if (fabs(cos(theta)) < 1.0e-20)
|
||||||
|
theta += 1.0e-10;
|
||||||
|
var psiDot = (q * sin(phi) + r * cos(phi)) / cos(theta);
|
||||||
|
|
||||||
|
return new Tuple<double, double, double>(degrees(phiDot), degrees(thetaDot), degrees(psiDot));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
|
@ -104,6 +104,13 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
//talk.SpeakAsync("Welcome to APM Planner");
|
//talk.SpeakAsync("Welcome to APM Planner");
|
||||||
|
|
||||||
|
try
|
||||||
|
{
|
||||||
|
checkForUpdate();
|
||||||
|
}
|
||||||
|
catch { Console.WriteLine("update check failed"); }
|
||||||
|
|
||||||
|
|
||||||
InitializeComponent();
|
InitializeComponent();
|
||||||
|
|
||||||
MyRenderer.currentpressed = MenuFlightData;
|
MyRenderer.currentpressed = MenuFlightData;
|
||||||
@ -1578,11 +1585,12 @@ namespace ArdupilotMega
|
|||||||
temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static string baseurl = "http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/";
|
||||||
|
|
||||||
public static void updatecheck(Label loadinglabel)
|
public static void updatecheck(Label loadinglabel)
|
||||||
{
|
{
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
string baseurl = "http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/";
|
|
||||||
bool update = updatecheck(loadinglabel, baseurl, "");
|
bool update = updatecheck(loadinglabel, baseurl, "");
|
||||||
System.Diagnostics.Process P = new System.Diagnostics.Process();
|
System.Diagnostics.Process P = new System.Diagnostics.Process();
|
||||||
if (MONO)
|
if (MONO)
|
||||||
@ -1629,6 +1637,67 @@ namespace ArdupilotMega
|
|||||||
Application.DoEvents();
|
Application.DoEvents();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private static void checkForUpdate()
|
||||||
|
{
|
||||||
|
string path = Path.GetFileNameWithoutExtension(Application.ExecutablePath) + ".exe";
|
||||||
|
|
||||||
|
// Create a request using a URL that can receive a post.
|
||||||
|
WebRequest request = WebRequest.Create(baseurl + path);
|
||||||
|
request.Timeout = 5000;
|
||||||
|
Console.Write(baseurl + path + " ");
|
||||||
|
// Set the Method property of the request to POST.
|
||||||
|
request.Method = "HEAD";
|
||||||
|
|
||||||
|
((HttpWebRequest)request).IfModifiedSince = File.GetLastWriteTimeUtc(path);
|
||||||
|
|
||||||
|
// Get the response.
|
||||||
|
WebResponse response = request.GetResponse();
|
||||||
|
// Display the status.
|
||||||
|
Console.WriteLine(((HttpWebResponse)response).StatusDescription);
|
||||||
|
// Get the stream containing content returned by the server.
|
||||||
|
//dataStream = response.GetResponseStream();
|
||||||
|
// Open the stream using a StreamReader for easy access.
|
||||||
|
|
||||||
|
bool getfile = false;
|
||||||
|
|
||||||
|
if (File.Exists(path))
|
||||||
|
{
|
||||||
|
FileInfo fi = new FileInfo(path);
|
||||||
|
|
||||||
|
Console.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
||||||
|
|
||||||
|
if (fi.Length != response.ContentLength) // && response.Headers[HttpResponseHeader.ETag] != "0")
|
||||||
|
{
|
||||||
|
StreamWriter sw = new StreamWriter(path + ".etag");
|
||||||
|
sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
||||||
|
sw.Close();
|
||||||
|
getfile = true;
|
||||||
|
Console.WriteLine("NEW FILE " + path);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
getfile = true;
|
||||||
|
Console.WriteLine("NEW FILE " + path);
|
||||||
|
// get it
|
||||||
|
}
|
||||||
|
|
||||||
|
response.Close();
|
||||||
|
|
||||||
|
if (getfile)
|
||||||
|
{
|
||||||
|
DialogResult dr = MessageBox.Show("Update Found\n\nDo you wish to update now?", "Update Now", MessageBoxButtons.YesNo);
|
||||||
|
if (dr == DialogResult.Yes)
|
||||||
|
{
|
||||||
|
GCSViews.Help.BUT_updatecheck_Click(null, null);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
private static bool updatecheck(Label loadinglabel, string baseurl, string subdir)
|
private static bool updatecheck(Label loadinglabel, string baseurl, string subdir)
|
||||||
{
|
{
|
||||||
bool update = false;
|
bool update = false;
|
||||||
|
@ -29,6 +29,19 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
//Common.linearRegression();
|
//Common.linearRegression();
|
||||||
|
|
||||||
|
var answer = HIL.Utils.EarthRatesToBodyRatesRyan(0, 0, 0, 0, 5, 0);
|
||||||
|
Console.WriteLine("roll {0:0.000} {1:0.000} {2:0.000} ", answer.Item1 , answer.Item2 , answer.Item3);
|
||||||
|
|
||||||
|
answer = HIL.Utils.EarthRatesToBodyRatesRyan(0, 0, 45, 2.5, 2.5, 0);
|
||||||
|
Console.WriteLine("roll {0:0.000} {1:0.000} {2:0.000} ", answer.Item1, answer.Item2, answer.Item3);
|
||||||
|
|
||||||
|
answer = HIL.Utils.EarthRatesToBodyRatesRyan(0, 0, 90, 5, 0, 0);
|
||||||
|
Console.WriteLine("roll {0:0.000} {1:0.000} {2:0.000} ", answer.Item1, answer.Item2, answer.Item3);
|
||||||
|
|
||||||
|
// Console.ReadLine();
|
||||||
|
|
||||||
|
//return;
|
||||||
|
|
||||||
Application.EnableVisualStyles();
|
Application.EnableVisualStyles();
|
||||||
Application.SetCompatibleTextRenderingDefault(false);
|
Application.SetCompatibleTextRenderingDefault(false);
|
||||||
try
|
try
|
||||||
|
@ -34,5 +34,5 @@ using System.Resources;
|
|||||||
// by using the '*' as shown below:
|
// by using the '*' as shown below:
|
||||||
// [assembly: AssemblyVersion("1.0.*")]
|
// [assembly: AssemblyVersion("1.0.*")]
|
||||||
[assembly: AssemblyVersion("1.0.0.0")]
|
[assembly: AssemblyVersion("1.0.0.0")]
|
||||||
[assembly: AssemblyFileVersion("1.1.26")]
|
[assembly: AssemblyFileVersion("1.1.27")]
|
||||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||||
|
532
Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs
generated
532
Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs
generated
@ -41,6 +41,16 @@
|
|||||||
this.CHK_revch4 = new System.Windows.Forms.CheckBox();
|
this.CHK_revch4 = new System.Windows.Forms.CheckBox();
|
||||||
this.CHK_revch2 = new System.Windows.Forms.CheckBox();
|
this.CHK_revch2 = new System.Windows.Forms.CheckBox();
|
||||||
this.CHK_revch1 = new System.Windows.Forms.CheckBox();
|
this.CHK_revch1 = new System.Windows.Forms.CheckBox();
|
||||||
|
this.BUT_Calibrateradio = new ArdupilotMega.MyButton();
|
||||||
|
this.BAR8 = new ArdupilotMega.HorizontalProgressBar2();
|
||||||
|
this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||||
|
this.BAR7 = new ArdupilotMega.HorizontalProgressBar2();
|
||||||
|
this.BAR6 = new ArdupilotMega.HorizontalProgressBar2();
|
||||||
|
this.BAR5 = new ArdupilotMega.HorizontalProgressBar2();
|
||||||
|
this.BARpitch = new ArdupilotMega.VerticalProgressBar2();
|
||||||
|
this.BARthrottle = new ArdupilotMega.VerticalProgressBar2();
|
||||||
|
this.BARyaw = new ArdupilotMega.HorizontalProgressBar2();
|
||||||
|
this.BARroll = new ArdupilotMega.HorizontalProgressBar2();
|
||||||
this.tabModes = new System.Windows.Forms.TabPage();
|
this.tabModes = new System.Windows.Forms.TabPage();
|
||||||
this.CB_simple6 = new System.Windows.Forms.CheckBox();
|
this.CB_simple6 = new System.Windows.Forms.CheckBox();
|
||||||
this.CB_simple5 = new System.Windows.Forms.CheckBox();
|
this.CB_simple5 = new System.Windows.Forms.CheckBox();
|
||||||
@ -70,6 +80,7 @@
|
|||||||
this.CMB_fmode2 = new System.Windows.Forms.ComboBox();
|
this.CMB_fmode2 = new System.Windows.Forms.ComboBox();
|
||||||
this.label1 = new System.Windows.Forms.Label();
|
this.label1 = new System.Windows.Forms.Label();
|
||||||
this.CMB_fmode1 = new System.Windows.Forms.ComboBox();
|
this.CMB_fmode1 = new System.Windows.Forms.ComboBox();
|
||||||
|
this.BUT_SaveModes = new ArdupilotMega.MyButton();
|
||||||
this.tabHardware = new System.Windows.Forms.TabPage();
|
this.tabHardware = new System.Windows.Forms.TabPage();
|
||||||
this.label27 = new System.Windows.Forms.Label();
|
this.label27 = new System.Windows.Forms.Label();
|
||||||
this.CMB_sonartype = new System.Windows.Forms.ComboBox();
|
this.CMB_sonartype = new System.Windows.Forms.ComboBox();
|
||||||
@ -85,16 +96,19 @@
|
|||||||
this.pictureBox3 = new System.Windows.Forms.PictureBox();
|
this.pictureBox3 = new System.Windows.Forms.PictureBox();
|
||||||
this.pictureBox1 = new System.Windows.Forms.PictureBox();
|
this.pictureBox1 = new System.Windows.Forms.PictureBox();
|
||||||
this.tabBattery = new System.Windows.Forms.TabPage();
|
this.tabBattery = new System.Windows.Forms.TabPage();
|
||||||
this.TXT_ampspervolt = new System.Windows.Forms.TextBox();
|
this.groupBox4 = new System.Windows.Forms.GroupBox();
|
||||||
this.TXT_divider = new System.Windows.Forms.TextBox();
|
|
||||||
this.TXT_voltage = new System.Windows.Forms.TextBox();
|
|
||||||
this.TXT_measuredvoltage = new System.Windows.Forms.TextBox();
|
|
||||||
this.TXT_inputvoltage = new System.Windows.Forms.TextBox();
|
|
||||||
this.label35 = new System.Windows.Forms.Label();
|
|
||||||
this.label34 = new System.Windows.Forms.Label();
|
|
||||||
this.label33 = new System.Windows.Forms.Label();
|
|
||||||
this.label32 = new System.Windows.Forms.Label();
|
|
||||||
this.label31 = new System.Windows.Forms.Label();
|
this.label31 = new System.Windows.Forms.Label();
|
||||||
|
this.label32 = new System.Windows.Forms.Label();
|
||||||
|
this.label33 = new System.Windows.Forms.Label();
|
||||||
|
this.TXT_ampspervolt = new System.Windows.Forms.TextBox();
|
||||||
|
this.label34 = new System.Windows.Forms.Label();
|
||||||
|
this.TXT_divider = new System.Windows.Forms.TextBox();
|
||||||
|
this.label35 = new System.Windows.Forms.Label();
|
||||||
|
this.TXT_voltage = new System.Windows.Forms.TextBox();
|
||||||
|
this.TXT_inputvoltage = new System.Windows.Forms.TextBox();
|
||||||
|
this.TXT_measuredvoltage = new System.Windows.Forms.TextBox();
|
||||||
|
this.label47 = new System.Windows.Forms.Label();
|
||||||
|
this.CMB_batmonsensortype = new System.Windows.Forms.ComboBox();
|
||||||
this.textBox3 = new System.Windows.Forms.TextBox();
|
this.textBox3 = new System.Windows.Forms.TextBox();
|
||||||
this.label29 = new System.Windows.Forms.Label();
|
this.label29 = new System.Windows.Forms.Label();
|
||||||
this.label30 = new System.Windows.Forms.Label();
|
this.label30 = new System.Windows.Forms.Label();
|
||||||
@ -107,7 +121,10 @@
|
|||||||
this.label15 = new System.Windows.Forms.Label();
|
this.label15 = new System.Windows.Forms.Label();
|
||||||
this.pictureBoxQuadX = new System.Windows.Forms.PictureBox();
|
this.pictureBoxQuadX = new System.Windows.Forms.PictureBox();
|
||||||
this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
|
this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
|
||||||
|
this.BUT_levelac2 = new ArdupilotMega.MyButton();
|
||||||
this.tabHeli = new System.Windows.Forms.TabPage();
|
this.tabHeli = new System.Windows.Forms.TabPage();
|
||||||
|
this.BUT_HS4save = new ArdupilotMega.MyButton();
|
||||||
|
this.BUT_swash_manual = new ArdupilotMega.MyButton();
|
||||||
this.groupBox3 = new System.Windows.Forms.GroupBox();
|
this.groupBox3 = new System.Windows.Forms.GroupBox();
|
||||||
this.label46 = new System.Windows.Forms.Label();
|
this.label46 = new System.Windows.Forms.Label();
|
||||||
this.label45 = new System.Windows.Forms.Label();
|
this.label45 = new System.Windows.Forms.Label();
|
||||||
@ -127,6 +144,7 @@
|
|||||||
this.COL_MIN_ = new System.Windows.Forms.TextBox();
|
this.COL_MIN_ = new System.Windows.Forms.TextBox();
|
||||||
this.COL_MID_ = new System.Windows.Forms.TextBox();
|
this.COL_MID_ = new System.Windows.Forms.TextBox();
|
||||||
this.COL_MAX_ = new System.Windows.Forms.TextBox();
|
this.COL_MAX_ = new System.Windows.Forms.TextBox();
|
||||||
|
this.BUT_0collective = new ArdupilotMega.MyButton();
|
||||||
this.HS4_TRIM = new System.Windows.Forms.NumericUpDown();
|
this.HS4_TRIM = new System.Windows.Forms.NumericUpDown();
|
||||||
this.HS3_TRIM = new System.Windows.Forms.NumericUpDown();
|
this.HS3_TRIM = new System.Windows.Forms.NumericUpDown();
|
||||||
this.HS2_TRIM = new System.Windows.Forms.NumericUpDown();
|
this.HS2_TRIM = new System.Windows.Forms.NumericUpDown();
|
||||||
@ -152,33 +170,16 @@
|
|||||||
this.HS2_REV = new System.Windows.Forms.CheckBox();
|
this.HS2_REV = new System.Windows.Forms.CheckBox();
|
||||||
this.HS1_REV = new System.Windows.Forms.CheckBox();
|
this.HS1_REV = new System.Windows.Forms.CheckBox();
|
||||||
this.label17 = new System.Windows.Forms.Label();
|
this.label17 = new System.Windows.Forms.Label();
|
||||||
this.tabReset = new System.Windows.Forms.TabPage();
|
|
||||||
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
|
|
||||||
this.CMB_batmonsensortype = new System.Windows.Forms.ComboBox();
|
|
||||||
this.BUT_Calibrateradio = new ArdupilotMega.MyButton();
|
|
||||||
this.BAR8 = new ArdupilotMega.HorizontalProgressBar2();
|
|
||||||
this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
|
||||||
this.BAR7 = new ArdupilotMega.HorizontalProgressBar2();
|
|
||||||
this.BAR6 = new ArdupilotMega.HorizontalProgressBar2();
|
|
||||||
this.BAR5 = new ArdupilotMega.HorizontalProgressBar2();
|
|
||||||
this.BARpitch = new ArdupilotMega.VerticalProgressBar2();
|
|
||||||
this.BARthrottle = new ArdupilotMega.VerticalProgressBar2();
|
|
||||||
this.BARyaw = new ArdupilotMega.HorizontalProgressBar2();
|
|
||||||
this.BARroll = new ArdupilotMega.HorizontalProgressBar2();
|
|
||||||
this.BUT_SaveModes = new ArdupilotMega.MyButton();
|
|
||||||
this.BUT_levelac2 = new ArdupilotMega.MyButton();
|
|
||||||
this.BUT_HS4save = new ArdupilotMega.MyButton();
|
|
||||||
this.BUT_swash_manual = new ArdupilotMega.MyButton();
|
|
||||||
this.BUT_0collective = new ArdupilotMega.MyButton();
|
|
||||||
this.HS4 = new ArdupilotMega.HorizontalProgressBar2();
|
this.HS4 = new ArdupilotMega.HorizontalProgressBar2();
|
||||||
this.HS3 = new ArdupilotMega.VerticalProgressBar2();
|
this.HS3 = new ArdupilotMega.VerticalProgressBar2();
|
||||||
this.Gservoloc = new AGaugeApp.AGauge();
|
this.Gservoloc = new AGaugeApp.AGauge();
|
||||||
|
this.tabReset = new System.Windows.Forms.TabPage();
|
||||||
this.BUT_reset = new ArdupilotMega.MyButton();
|
this.BUT_reset = new ArdupilotMega.MyButton();
|
||||||
this.label47 = new System.Windows.Forms.Label();
|
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
|
||||||
this.groupBox4 = new System.Windows.Forms.GroupBox();
|
|
||||||
this.tabControl1.SuspendLayout();
|
this.tabControl1.SuspendLayout();
|
||||||
this.tabRadioIn.SuspendLayout();
|
this.tabRadioIn.SuspendLayout();
|
||||||
this.groupBoxElevons.SuspendLayout();
|
this.groupBoxElevons.SuspendLayout();
|
||||||
|
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
|
||||||
this.tabModes.SuspendLayout();
|
this.tabModes.SuspendLayout();
|
||||||
this.tabHardware.SuspendLayout();
|
this.tabHardware.SuspendLayout();
|
||||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit();
|
((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit();
|
||||||
@ -186,6 +187,7 @@
|
|||||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).BeginInit();
|
((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).BeginInit();
|
||||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit();
|
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit();
|
||||||
this.tabBattery.SuspendLayout();
|
this.tabBattery.SuspendLayout();
|
||||||
|
this.groupBox4.SuspendLayout();
|
||||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).BeginInit();
|
((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).BeginInit();
|
||||||
this.tabArducopter.SuspendLayout();
|
this.tabArducopter.SuspendLayout();
|
||||||
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit();
|
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit();
|
||||||
@ -199,8 +201,6 @@
|
|||||||
((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).BeginInit();
|
((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).BeginInit();
|
||||||
((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).BeginInit();
|
((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).BeginInit();
|
||||||
this.tabReset.SuspendLayout();
|
this.tabReset.SuspendLayout();
|
||||||
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
|
|
||||||
this.groupBox4.SuspendLayout();
|
|
||||||
this.SuspendLayout();
|
this.SuspendLayout();
|
||||||
//
|
//
|
||||||
// tabControl1
|
// tabControl1
|
||||||
@ -306,6 +306,137 @@
|
|||||||
this.CHK_revch1.UseVisualStyleBackColor = true;
|
this.CHK_revch1.UseVisualStyleBackColor = true;
|
||||||
this.CHK_revch1.CheckedChanged += new System.EventHandler(this.CHK_revch1_CheckedChanged);
|
this.CHK_revch1.CheckedChanged += new System.EventHandler(this.CHK_revch1_CheckedChanged);
|
||||||
//
|
//
|
||||||
|
// BUT_Calibrateradio
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.BUT_Calibrateradio, "BUT_Calibrateradio");
|
||||||
|
this.BUT_Calibrateradio.Name = "BUT_Calibrateradio";
|
||||||
|
this.BUT_Calibrateradio.UseVisualStyleBackColor = true;
|
||||||
|
this.BUT_Calibrateradio.Click += new System.EventHandler(this.BUT_Calibrateradio_Click);
|
||||||
|
//
|
||||||
|
// BAR8
|
||||||
|
//
|
||||||
|
this.BAR8.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||||
|
this.BAR8.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||||
|
this.BAR8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch8in", true));
|
||||||
|
this.BAR8.Label = "Radio 8";
|
||||||
|
resources.ApplyResources(this.BAR8, "BAR8");
|
||||||
|
this.BAR8.Maximum = 2200;
|
||||||
|
this.BAR8.maxline = 0;
|
||||||
|
this.BAR8.Minimum = 800;
|
||||||
|
this.BAR8.minline = 0;
|
||||||
|
this.BAR8.Name = "BAR8";
|
||||||
|
this.BAR8.Value = 1500;
|
||||||
|
this.BAR8.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||||
|
//
|
||||||
|
// currentStateBindingSource
|
||||||
|
//
|
||||||
|
this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState);
|
||||||
|
//
|
||||||
|
// BAR7
|
||||||
|
//
|
||||||
|
this.BAR7.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||||
|
this.BAR7.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||||
|
this.BAR7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch7in", true));
|
||||||
|
this.BAR7.Label = "Radio 7";
|
||||||
|
resources.ApplyResources(this.BAR7, "BAR7");
|
||||||
|
this.BAR7.Maximum = 2200;
|
||||||
|
this.BAR7.maxline = 0;
|
||||||
|
this.BAR7.Minimum = 800;
|
||||||
|
this.BAR7.minline = 0;
|
||||||
|
this.BAR7.Name = "BAR7";
|
||||||
|
this.BAR7.Value = 1500;
|
||||||
|
this.BAR7.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||||
|
//
|
||||||
|
// BAR6
|
||||||
|
//
|
||||||
|
this.BAR6.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||||
|
this.BAR6.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||||
|
this.BAR6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch6in", true));
|
||||||
|
this.BAR6.Label = "Radio 6";
|
||||||
|
resources.ApplyResources(this.BAR6, "BAR6");
|
||||||
|
this.BAR6.Maximum = 2200;
|
||||||
|
this.BAR6.maxline = 0;
|
||||||
|
this.BAR6.Minimum = 800;
|
||||||
|
this.BAR6.minline = 0;
|
||||||
|
this.BAR6.Name = "BAR6";
|
||||||
|
this.BAR6.Value = 1500;
|
||||||
|
this.BAR6.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||||
|
//
|
||||||
|
// BAR5
|
||||||
|
//
|
||||||
|
this.BAR5.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||||
|
this.BAR5.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||||
|
this.BAR5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch5in", true));
|
||||||
|
this.BAR5.Label = "Radio 5";
|
||||||
|
resources.ApplyResources(this.BAR5, "BAR5");
|
||||||
|
this.BAR5.Maximum = 2200;
|
||||||
|
this.BAR5.maxline = 0;
|
||||||
|
this.BAR5.Minimum = 800;
|
||||||
|
this.BAR5.minline = 0;
|
||||||
|
this.BAR5.Name = "BAR5";
|
||||||
|
this.BAR5.Value = 1500;
|
||||||
|
this.BAR5.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||||
|
//
|
||||||
|
// BARpitch
|
||||||
|
//
|
||||||
|
this.BARpitch.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||||
|
this.BARpitch.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||||
|
this.BARpitch.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch2in", true));
|
||||||
|
this.BARpitch.Label = "Pitch";
|
||||||
|
resources.ApplyResources(this.BARpitch, "BARpitch");
|
||||||
|
this.BARpitch.Maximum = 2200;
|
||||||
|
this.BARpitch.maxline = 0;
|
||||||
|
this.BARpitch.Minimum = 800;
|
||||||
|
this.BARpitch.minline = 0;
|
||||||
|
this.BARpitch.Name = "BARpitch";
|
||||||
|
this.BARpitch.Value = 1500;
|
||||||
|
this.BARpitch.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||||
|
//
|
||||||
|
// BARthrottle
|
||||||
|
//
|
||||||
|
this.BARthrottle.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
|
||||||
|
this.BARthrottle.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||||
|
this.BARthrottle.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true));
|
||||||
|
this.BARthrottle.Label = "Throttle";
|
||||||
|
resources.ApplyResources(this.BARthrottle, "BARthrottle");
|
||||||
|
this.BARthrottle.Maximum = 2200;
|
||||||
|
this.BARthrottle.maxline = 0;
|
||||||
|
this.BARthrottle.Minimum = 800;
|
||||||
|
this.BARthrottle.minline = 0;
|
||||||
|
this.BARthrottle.Name = "BARthrottle";
|
||||||
|
this.BARthrottle.Value = 1000;
|
||||||
|
this.BARthrottle.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
|
||||||
|
//
|
||||||
|
// BARyaw
|
||||||
|
//
|
||||||
|
this.BARyaw.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||||
|
this.BARyaw.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||||
|
this.BARyaw.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true));
|
||||||
|
this.BARyaw.Label = "Yaw";
|
||||||
|
resources.ApplyResources(this.BARyaw, "BARyaw");
|
||||||
|
this.BARyaw.Maximum = 2200;
|
||||||
|
this.BARyaw.maxline = 0;
|
||||||
|
this.BARyaw.Minimum = 800;
|
||||||
|
this.BARyaw.minline = 0;
|
||||||
|
this.BARyaw.Name = "BARyaw";
|
||||||
|
this.BARyaw.Value = 1500;
|
||||||
|
this.BARyaw.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||||
|
//
|
||||||
|
// BARroll
|
||||||
|
//
|
||||||
|
this.BARroll.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||||
|
this.BARroll.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||||
|
this.BARroll.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch1in", true));
|
||||||
|
this.BARroll.Label = "Roll";
|
||||||
|
resources.ApplyResources(this.BARroll, "BARroll");
|
||||||
|
this.BARroll.Maximum = 2200;
|
||||||
|
this.BARroll.maxline = 0;
|
||||||
|
this.BARroll.Minimum = 800;
|
||||||
|
this.BARroll.minline = 0;
|
||||||
|
this.BARroll.Name = "BARroll";
|
||||||
|
this.BARroll.Value = 1500;
|
||||||
|
this.BARroll.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||||
|
//
|
||||||
// tabModes
|
// tabModes
|
||||||
//
|
//
|
||||||
this.tabModes.Controls.Add(this.CB_simple6);
|
this.tabModes.Controls.Add(this.CB_simple6);
|
||||||
@ -512,6 +643,13 @@
|
|||||||
resources.ApplyResources(this.CMB_fmode1, "CMB_fmode1");
|
resources.ApplyResources(this.CMB_fmode1, "CMB_fmode1");
|
||||||
this.CMB_fmode1.Name = "CMB_fmode1";
|
this.CMB_fmode1.Name = "CMB_fmode1";
|
||||||
//
|
//
|
||||||
|
// BUT_SaveModes
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.BUT_SaveModes, "BUT_SaveModes");
|
||||||
|
this.BUT_SaveModes.Name = "BUT_SaveModes";
|
||||||
|
this.BUT_SaveModes.UseVisualStyleBackColor = true;
|
||||||
|
this.BUT_SaveModes.Click += new System.EventHandler(this.BUT_SaveModes_Click);
|
||||||
|
//
|
||||||
// tabHardware
|
// tabHardware
|
||||||
//
|
//
|
||||||
this.tabHardware.BackColor = System.Drawing.Color.DarkRed;
|
this.tabHardware.BackColor = System.Drawing.Color.DarkRed;
|
||||||
@ -644,6 +782,37 @@
|
|||||||
this.tabBattery.Name = "tabBattery";
|
this.tabBattery.Name = "tabBattery";
|
||||||
this.tabBattery.UseVisualStyleBackColor = true;
|
this.tabBattery.UseVisualStyleBackColor = true;
|
||||||
//
|
//
|
||||||
|
// groupBox4
|
||||||
|
//
|
||||||
|
this.groupBox4.Controls.Add(this.label31);
|
||||||
|
this.groupBox4.Controls.Add(this.label32);
|
||||||
|
this.groupBox4.Controls.Add(this.label33);
|
||||||
|
this.groupBox4.Controls.Add(this.TXT_ampspervolt);
|
||||||
|
this.groupBox4.Controls.Add(this.label34);
|
||||||
|
this.groupBox4.Controls.Add(this.TXT_divider);
|
||||||
|
this.groupBox4.Controls.Add(this.label35);
|
||||||
|
this.groupBox4.Controls.Add(this.TXT_voltage);
|
||||||
|
this.groupBox4.Controls.Add(this.TXT_inputvoltage);
|
||||||
|
this.groupBox4.Controls.Add(this.TXT_measuredvoltage);
|
||||||
|
resources.ApplyResources(this.groupBox4, "groupBox4");
|
||||||
|
this.groupBox4.Name = "groupBox4";
|
||||||
|
this.groupBox4.TabStop = false;
|
||||||
|
//
|
||||||
|
// label31
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.label31, "label31");
|
||||||
|
this.label31.Name = "label31";
|
||||||
|
//
|
||||||
|
// label32
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.label32, "label32");
|
||||||
|
this.label32.Name = "label32";
|
||||||
|
//
|
||||||
|
// label33
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.label33, "label33");
|
||||||
|
this.label33.Name = "label33";
|
||||||
|
//
|
||||||
// TXT_ampspervolt
|
// TXT_ampspervolt
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.TXT_ampspervolt, "TXT_ampspervolt");
|
resources.ApplyResources(this.TXT_ampspervolt, "TXT_ampspervolt");
|
||||||
@ -651,6 +820,11 @@
|
|||||||
this.TXT_ampspervolt.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_ampspervolt_Validating);
|
this.TXT_ampspervolt.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_ampspervolt_Validating);
|
||||||
this.TXT_ampspervolt.Validated += new System.EventHandler(this.TXT_ampspervolt_Validated);
|
this.TXT_ampspervolt.Validated += new System.EventHandler(this.TXT_ampspervolt_Validated);
|
||||||
//
|
//
|
||||||
|
// label34
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.label34, "label34");
|
||||||
|
this.label34.Name = "label34";
|
||||||
|
//
|
||||||
// TXT_divider
|
// TXT_divider
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.TXT_divider, "TXT_divider");
|
resources.ApplyResources(this.TXT_divider, "TXT_divider");
|
||||||
@ -658,6 +832,11 @@
|
|||||||
this.TXT_divider.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_divider_Validating);
|
this.TXT_divider.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_divider_Validating);
|
||||||
this.TXT_divider.Validated += new System.EventHandler(this.TXT_divider_Validated);
|
this.TXT_divider.Validated += new System.EventHandler(this.TXT_divider_Validated);
|
||||||
//
|
//
|
||||||
|
// label35
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.label35, "label35");
|
||||||
|
this.label35.Name = "label35";
|
||||||
|
//
|
||||||
// TXT_voltage
|
// TXT_voltage
|
||||||
//
|
//
|
||||||
this.TXT_voltage.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.currentStateBindingSource, "battery_voltage", true));
|
this.TXT_voltage.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.currentStateBindingSource, "battery_voltage", true));
|
||||||
@ -665,13 +844,6 @@
|
|||||||
this.TXT_voltage.Name = "TXT_voltage";
|
this.TXT_voltage.Name = "TXT_voltage";
|
||||||
this.TXT_voltage.ReadOnly = true;
|
this.TXT_voltage.ReadOnly = true;
|
||||||
//
|
//
|
||||||
// TXT_measuredvoltage
|
|
||||||
//
|
|
||||||
resources.ApplyResources(this.TXT_measuredvoltage, "TXT_measuredvoltage");
|
|
||||||
this.TXT_measuredvoltage.Name = "TXT_measuredvoltage";
|
|
||||||
this.TXT_measuredvoltage.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_measuredvoltage_Validating);
|
|
||||||
this.TXT_measuredvoltage.Validated += new System.EventHandler(this.TXT_measuredvoltage_Validated);
|
|
||||||
//
|
|
||||||
// TXT_inputvoltage
|
// TXT_inputvoltage
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.TXT_inputvoltage, "TXT_inputvoltage");
|
resources.ApplyResources(this.TXT_inputvoltage, "TXT_inputvoltage");
|
||||||
@ -679,30 +851,29 @@
|
|||||||
this.TXT_inputvoltage.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_inputvoltage_Validating);
|
this.TXT_inputvoltage.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_inputvoltage_Validating);
|
||||||
this.TXT_inputvoltage.Validated += new System.EventHandler(this.TXT_inputvoltage_Validated);
|
this.TXT_inputvoltage.Validated += new System.EventHandler(this.TXT_inputvoltage_Validated);
|
||||||
//
|
//
|
||||||
// label35
|
// TXT_measuredvoltage
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.label35, "label35");
|
resources.ApplyResources(this.TXT_measuredvoltage, "TXT_measuredvoltage");
|
||||||
this.label35.Name = "label35";
|
this.TXT_measuredvoltage.Name = "TXT_measuredvoltage";
|
||||||
|
this.TXT_measuredvoltage.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_measuredvoltage_Validating);
|
||||||
|
this.TXT_measuredvoltage.Validated += new System.EventHandler(this.TXT_measuredvoltage_Validated);
|
||||||
//
|
//
|
||||||
// label34
|
// label47
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.label34, "label34");
|
resources.ApplyResources(this.label47, "label47");
|
||||||
this.label34.Name = "label34";
|
this.label47.Name = "label47";
|
||||||
//
|
//
|
||||||
// label33
|
// CMB_batmonsensortype
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.label33, "label33");
|
this.CMB_batmonsensortype.FormattingEnabled = true;
|
||||||
this.label33.Name = "label33";
|
this.CMB_batmonsensortype.Items.AddRange(new object[] {
|
||||||
//
|
resources.GetString("CMB_batmonsensortype.Items"),
|
||||||
// label32
|
resources.GetString("CMB_batmonsensortype.Items1"),
|
||||||
//
|
resources.GetString("CMB_batmonsensortype.Items2"),
|
||||||
resources.ApplyResources(this.label32, "label32");
|
resources.GetString("CMB_batmonsensortype.Items3")});
|
||||||
this.label32.Name = "label32";
|
resources.ApplyResources(this.CMB_batmonsensortype, "CMB_batmonsensortype");
|
||||||
//
|
this.CMB_batmonsensortype.Name = "CMB_batmonsensortype";
|
||||||
// label31
|
this.CMB_batmonsensortype.SelectedIndexChanged += new System.EventHandler(this.CMB_batmonsensortype_SelectedIndexChanged);
|
||||||
//
|
|
||||||
resources.ApplyResources(this.label31, "label31");
|
|
||||||
this.label31.Name = "label31";
|
|
||||||
//
|
//
|
||||||
// textBox3
|
// textBox3
|
||||||
//
|
//
|
||||||
@ -792,6 +963,13 @@
|
|||||||
this.pictureBoxQuad.TabStop = false;
|
this.pictureBoxQuad.TabStop = false;
|
||||||
this.pictureBoxQuad.Click += new System.EventHandler(this.pictureBoxQuad_Click);
|
this.pictureBoxQuad.Click += new System.EventHandler(this.pictureBoxQuad_Click);
|
||||||
//
|
//
|
||||||
|
// BUT_levelac2
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.BUT_levelac2, "BUT_levelac2");
|
||||||
|
this.BUT_levelac2.Name = "BUT_levelac2";
|
||||||
|
this.BUT_levelac2.UseVisualStyleBackColor = true;
|
||||||
|
this.BUT_levelac2.Click += new System.EventHandler(this.BUT_levelac2_Click);
|
||||||
|
//
|
||||||
// tabHeli
|
// tabHeli
|
||||||
//
|
//
|
||||||
this.tabHeli.Controls.Add(this.BUT_HS4save);
|
this.tabHeli.Controls.Add(this.BUT_HS4save);
|
||||||
@ -835,6 +1013,20 @@
|
|||||||
this.tabHeli.UseVisualStyleBackColor = true;
|
this.tabHeli.UseVisualStyleBackColor = true;
|
||||||
this.tabHeli.Click += new System.EventHandler(this.tabHeli_Click);
|
this.tabHeli.Click += new System.EventHandler(this.tabHeli_Click);
|
||||||
//
|
//
|
||||||
|
// BUT_HS4save
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save");
|
||||||
|
this.BUT_HS4save.Name = "BUT_HS4save";
|
||||||
|
this.BUT_HS4save.UseVisualStyleBackColor = true;
|
||||||
|
this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click);
|
||||||
|
//
|
||||||
|
// BUT_swash_manual
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual");
|
||||||
|
this.BUT_swash_manual.Name = "BUT_swash_manual";
|
||||||
|
this.BUT_swash_manual.UseVisualStyleBackColor = true;
|
||||||
|
this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click);
|
||||||
|
//
|
||||||
// groupBox3
|
// groupBox3
|
||||||
//
|
//
|
||||||
this.groupBox3.Controls.Add(this.label46);
|
this.groupBox3.Controls.Add(this.label46);
|
||||||
@ -963,6 +1155,13 @@
|
|||||||
this.COL_MAX_.Leave += new System.EventHandler(this.COL_MAX__Leave);
|
this.COL_MAX_.Leave += new System.EventHandler(this.COL_MAX__Leave);
|
||||||
this.COL_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
this.COL_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
||||||
//
|
//
|
||||||
|
// BUT_0collective
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.BUT_0collective, "BUT_0collective");
|
||||||
|
this.BUT_0collective.Name = "BUT_0collective";
|
||||||
|
this.BUT_0collective.UseVisualStyleBackColor = true;
|
||||||
|
this.BUT_0collective.Click += new System.EventHandler(this.BUT_0collective_Click);
|
||||||
|
//
|
||||||
// HS4_TRIM
|
// HS4_TRIM
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.HS4_TRIM, "HS4_TRIM");
|
resources.ApplyResources(this.HS4_TRIM, "HS4_TRIM");
|
||||||
@ -1165,191 +1364,6 @@
|
|||||||
resources.ApplyResources(this.label17, "label17");
|
resources.ApplyResources(this.label17, "label17");
|
||||||
this.label17.Name = "label17";
|
this.label17.Name = "label17";
|
||||||
//
|
//
|
||||||
// tabReset
|
|
||||||
//
|
|
||||||
this.tabReset.Controls.Add(this.BUT_reset);
|
|
||||||
resources.ApplyResources(this.tabReset, "tabReset");
|
|
||||||
this.tabReset.Name = "tabReset";
|
|
||||||
this.tabReset.UseVisualStyleBackColor = true;
|
|
||||||
//
|
|
||||||
// CMB_batmonsensortype
|
|
||||||
//
|
|
||||||
this.CMB_batmonsensortype.FormattingEnabled = true;
|
|
||||||
this.CMB_batmonsensortype.Items.AddRange(new object[] {
|
|
||||||
resources.GetString("CMB_batmonsensortype.Items"),
|
|
||||||
resources.GetString("CMB_batmonsensortype.Items1"),
|
|
||||||
resources.GetString("CMB_batmonsensortype.Items2"),
|
|
||||||
resources.GetString("CMB_batmonsensortype.Items3")});
|
|
||||||
resources.ApplyResources(this.CMB_batmonsensortype, "CMB_batmonsensortype");
|
|
||||||
this.CMB_batmonsensortype.Name = "CMB_batmonsensortype";
|
|
||||||
this.CMB_batmonsensortype.SelectedIndexChanged += new System.EventHandler(this.CMB_batmonsensortype_SelectedIndexChanged);
|
|
||||||
//
|
|
||||||
// BUT_Calibrateradio
|
|
||||||
//
|
|
||||||
resources.ApplyResources(this.BUT_Calibrateradio, "BUT_Calibrateradio");
|
|
||||||
this.BUT_Calibrateradio.Name = "BUT_Calibrateradio";
|
|
||||||
this.BUT_Calibrateradio.UseVisualStyleBackColor = true;
|
|
||||||
this.BUT_Calibrateradio.Click += new System.EventHandler(this.BUT_Calibrateradio_Click);
|
|
||||||
//
|
|
||||||
// BAR8
|
|
||||||
//
|
|
||||||
this.BAR8.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
|
||||||
this.BAR8.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
|
||||||
this.BAR8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch8in", true));
|
|
||||||
this.BAR8.Label = "Radio 8";
|
|
||||||
resources.ApplyResources(this.BAR8, "BAR8");
|
|
||||||
this.BAR8.Maximum = 2200;
|
|
||||||
this.BAR8.maxline = 0;
|
|
||||||
this.BAR8.Minimum = 800;
|
|
||||||
this.BAR8.minline = 0;
|
|
||||||
this.BAR8.Name = "BAR8";
|
|
||||||
this.BAR8.Value = 1500;
|
|
||||||
this.BAR8.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
|
||||||
//
|
|
||||||
// currentStateBindingSource
|
|
||||||
//
|
|
||||||
this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState);
|
|
||||||
//
|
|
||||||
// BAR7
|
|
||||||
//
|
|
||||||
this.BAR7.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
|
||||||
this.BAR7.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
|
||||||
this.BAR7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch7in", true));
|
|
||||||
this.BAR7.Label = "Radio 7";
|
|
||||||
resources.ApplyResources(this.BAR7, "BAR7");
|
|
||||||
this.BAR7.Maximum = 2200;
|
|
||||||
this.BAR7.maxline = 0;
|
|
||||||
this.BAR7.Minimum = 800;
|
|
||||||
this.BAR7.minline = 0;
|
|
||||||
this.BAR7.Name = "BAR7";
|
|
||||||
this.BAR7.Value = 1500;
|
|
||||||
this.BAR7.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
|
||||||
//
|
|
||||||
// BAR6
|
|
||||||
//
|
|
||||||
this.BAR6.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
|
||||||
this.BAR6.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
|
||||||
this.BAR6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch6in", true));
|
|
||||||
this.BAR6.Label = "Radio 6";
|
|
||||||
resources.ApplyResources(this.BAR6, "BAR6");
|
|
||||||
this.BAR6.Maximum = 2200;
|
|
||||||
this.BAR6.maxline = 0;
|
|
||||||
this.BAR6.Minimum = 800;
|
|
||||||
this.BAR6.minline = 0;
|
|
||||||
this.BAR6.Name = "BAR6";
|
|
||||||
this.BAR6.Value = 1500;
|
|
||||||
this.BAR6.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
|
||||||
//
|
|
||||||
// BAR5
|
|
||||||
//
|
|
||||||
this.BAR5.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
|
||||||
this.BAR5.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
|
||||||
this.BAR5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch5in", true));
|
|
||||||
this.BAR5.Label = "Radio 5";
|
|
||||||
resources.ApplyResources(this.BAR5, "BAR5");
|
|
||||||
this.BAR5.Maximum = 2200;
|
|
||||||
this.BAR5.maxline = 0;
|
|
||||||
this.BAR5.Minimum = 800;
|
|
||||||
this.BAR5.minline = 0;
|
|
||||||
this.BAR5.Name = "BAR5";
|
|
||||||
this.BAR5.Value = 1500;
|
|
||||||
this.BAR5.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
|
||||||
//
|
|
||||||
// BARpitch
|
|
||||||
//
|
|
||||||
this.BARpitch.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
|
||||||
this.BARpitch.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
|
||||||
this.BARpitch.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch2in", true));
|
|
||||||
this.BARpitch.Label = "Pitch";
|
|
||||||
resources.ApplyResources(this.BARpitch, "BARpitch");
|
|
||||||
this.BARpitch.Maximum = 2200;
|
|
||||||
this.BARpitch.maxline = 0;
|
|
||||||
this.BARpitch.Minimum = 800;
|
|
||||||
this.BARpitch.minline = 0;
|
|
||||||
this.BARpitch.Name = "BARpitch";
|
|
||||||
this.BARpitch.Value = 1500;
|
|
||||||
this.BARpitch.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
|
||||||
//
|
|
||||||
// BARthrottle
|
|
||||||
//
|
|
||||||
this.BARthrottle.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
|
|
||||||
this.BARthrottle.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
|
||||||
this.BARthrottle.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true));
|
|
||||||
this.BARthrottle.Label = "Throttle";
|
|
||||||
resources.ApplyResources(this.BARthrottle, "BARthrottle");
|
|
||||||
this.BARthrottle.Maximum = 2200;
|
|
||||||
this.BARthrottle.maxline = 0;
|
|
||||||
this.BARthrottle.Minimum = 800;
|
|
||||||
this.BARthrottle.minline = 0;
|
|
||||||
this.BARthrottle.Name = "BARthrottle";
|
|
||||||
this.BARthrottle.Value = 1000;
|
|
||||||
this.BARthrottle.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
|
|
||||||
//
|
|
||||||
// BARyaw
|
|
||||||
//
|
|
||||||
this.BARyaw.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
|
||||||
this.BARyaw.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
|
||||||
this.BARyaw.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true));
|
|
||||||
this.BARyaw.Label = "Yaw";
|
|
||||||
resources.ApplyResources(this.BARyaw, "BARyaw");
|
|
||||||
this.BARyaw.Maximum = 2200;
|
|
||||||
this.BARyaw.maxline = 0;
|
|
||||||
this.BARyaw.Minimum = 800;
|
|
||||||
this.BARyaw.minline = 0;
|
|
||||||
this.BARyaw.Name = "BARyaw";
|
|
||||||
this.BARyaw.Value = 1500;
|
|
||||||
this.BARyaw.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
|
||||||
//
|
|
||||||
// BARroll
|
|
||||||
//
|
|
||||||
this.BARroll.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
|
||||||
this.BARroll.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
|
||||||
this.BARroll.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch1in", true));
|
|
||||||
this.BARroll.Label = "Roll";
|
|
||||||
resources.ApplyResources(this.BARroll, "BARroll");
|
|
||||||
this.BARroll.Maximum = 2200;
|
|
||||||
this.BARroll.maxline = 0;
|
|
||||||
this.BARroll.Minimum = 800;
|
|
||||||
this.BARroll.minline = 0;
|
|
||||||
this.BARroll.Name = "BARroll";
|
|
||||||
this.BARroll.Value = 1500;
|
|
||||||
this.BARroll.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
|
||||||
//
|
|
||||||
// BUT_SaveModes
|
|
||||||
//
|
|
||||||
resources.ApplyResources(this.BUT_SaveModes, "BUT_SaveModes");
|
|
||||||
this.BUT_SaveModes.Name = "BUT_SaveModes";
|
|
||||||
this.BUT_SaveModes.UseVisualStyleBackColor = true;
|
|
||||||
this.BUT_SaveModes.Click += new System.EventHandler(this.BUT_SaveModes_Click);
|
|
||||||
//
|
|
||||||
// BUT_levelac2
|
|
||||||
//
|
|
||||||
resources.ApplyResources(this.BUT_levelac2, "BUT_levelac2");
|
|
||||||
this.BUT_levelac2.Name = "BUT_levelac2";
|
|
||||||
this.BUT_levelac2.UseVisualStyleBackColor = true;
|
|
||||||
this.BUT_levelac2.Click += new System.EventHandler(this.BUT_levelac2_Click);
|
|
||||||
//
|
|
||||||
// BUT_HS4save
|
|
||||||
//
|
|
||||||
resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save");
|
|
||||||
this.BUT_HS4save.Name = "BUT_HS4save";
|
|
||||||
this.BUT_HS4save.UseVisualStyleBackColor = true;
|
|
||||||
this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click);
|
|
||||||
//
|
|
||||||
// BUT_swash_manual
|
|
||||||
//
|
|
||||||
resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual");
|
|
||||||
this.BUT_swash_manual.Name = "BUT_swash_manual";
|
|
||||||
this.BUT_swash_manual.UseVisualStyleBackColor = true;
|
|
||||||
this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click);
|
|
||||||
//
|
|
||||||
// BUT_0collective
|
|
||||||
//
|
|
||||||
resources.ApplyResources(this.BUT_0collective, "BUT_0collective");
|
|
||||||
this.BUT_0collective.Name = "BUT_0collective";
|
|
||||||
this.BUT_0collective.UseVisualStyleBackColor = true;
|
|
||||||
this.BUT_0collective.Click += new System.EventHandler(this.BUT_0collective_Click);
|
|
||||||
//
|
|
||||||
// HS4
|
// HS4
|
||||||
//
|
//
|
||||||
this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
|
this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
|
||||||
@ -1525,6 +1539,13 @@
|
|||||||
this.Gservoloc.Value2 = 180F;
|
this.Gservoloc.Value2 = 180F;
|
||||||
this.Gservoloc.Value3 = 0F;
|
this.Gservoloc.Value3 = 0F;
|
||||||
//
|
//
|
||||||
|
// tabReset
|
||||||
|
//
|
||||||
|
this.tabReset.Controls.Add(this.BUT_reset);
|
||||||
|
resources.ApplyResources(this.tabReset, "tabReset");
|
||||||
|
this.tabReset.Name = "tabReset";
|
||||||
|
this.tabReset.UseVisualStyleBackColor = true;
|
||||||
|
//
|
||||||
// BUT_reset
|
// BUT_reset
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.BUT_reset, "BUT_reset");
|
resources.ApplyResources(this.BUT_reset, "BUT_reset");
|
||||||
@ -1533,27 +1554,6 @@
|
|||||||
this.BUT_reset.UseVisualStyleBackColor = true;
|
this.BUT_reset.UseVisualStyleBackColor = true;
|
||||||
this.BUT_reset.Click += new System.EventHandler(this.BUT_reset_Click);
|
this.BUT_reset.Click += new System.EventHandler(this.BUT_reset_Click);
|
||||||
//
|
//
|
||||||
// label47
|
|
||||||
//
|
|
||||||
resources.ApplyResources(this.label47, "label47");
|
|
||||||
this.label47.Name = "label47";
|
|
||||||
//
|
|
||||||
// groupBox4
|
|
||||||
//
|
|
||||||
this.groupBox4.Controls.Add(this.label31);
|
|
||||||
this.groupBox4.Controls.Add(this.label32);
|
|
||||||
this.groupBox4.Controls.Add(this.label33);
|
|
||||||
this.groupBox4.Controls.Add(this.TXT_ampspervolt);
|
|
||||||
this.groupBox4.Controls.Add(this.label34);
|
|
||||||
this.groupBox4.Controls.Add(this.TXT_divider);
|
|
||||||
this.groupBox4.Controls.Add(this.label35);
|
|
||||||
this.groupBox4.Controls.Add(this.TXT_voltage);
|
|
||||||
this.groupBox4.Controls.Add(this.TXT_inputvoltage);
|
|
||||||
this.groupBox4.Controls.Add(this.TXT_measuredvoltage);
|
|
||||||
resources.ApplyResources(this.groupBox4, "groupBox4");
|
|
||||||
this.groupBox4.Name = "groupBox4";
|
|
||||||
this.groupBox4.TabStop = false;
|
|
||||||
//
|
|
||||||
// Setup
|
// Setup
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this, "$this");
|
resources.ApplyResources(this, "$this");
|
||||||
@ -1568,6 +1568,7 @@
|
|||||||
this.tabRadioIn.PerformLayout();
|
this.tabRadioIn.PerformLayout();
|
||||||
this.groupBoxElevons.ResumeLayout(false);
|
this.groupBoxElevons.ResumeLayout(false);
|
||||||
this.groupBoxElevons.PerformLayout();
|
this.groupBoxElevons.PerformLayout();
|
||||||
|
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
|
||||||
this.tabModes.ResumeLayout(false);
|
this.tabModes.ResumeLayout(false);
|
||||||
this.tabModes.PerformLayout();
|
this.tabModes.PerformLayout();
|
||||||
this.tabHardware.ResumeLayout(false);
|
this.tabHardware.ResumeLayout(false);
|
||||||
@ -1578,6 +1579,8 @@
|
|||||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit();
|
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit();
|
||||||
this.tabBattery.ResumeLayout(false);
|
this.tabBattery.ResumeLayout(false);
|
||||||
this.tabBattery.PerformLayout();
|
this.tabBattery.PerformLayout();
|
||||||
|
this.groupBox4.ResumeLayout(false);
|
||||||
|
this.groupBox4.PerformLayout();
|
||||||
((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).EndInit();
|
((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).EndInit();
|
||||||
this.tabArducopter.ResumeLayout(false);
|
this.tabArducopter.ResumeLayout(false);
|
||||||
this.tabArducopter.PerformLayout();
|
this.tabArducopter.PerformLayout();
|
||||||
@ -1596,9 +1599,6 @@
|
|||||||
((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).EndInit();
|
((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).EndInit();
|
||||||
((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).EndInit();
|
((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).EndInit();
|
||||||
this.tabReset.ResumeLayout(false);
|
this.tabReset.ResumeLayout(false);
|
||||||
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
|
|
||||||
this.groupBox4.ResumeLayout(false);
|
|
||||||
this.groupBox4.PerformLayout();
|
|
||||||
this.ResumeLayout(false);
|
this.ResumeLayout(false);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -477,6 +477,12 @@ namespace ArdupilotMega.Setup
|
|||||||
string option = MainV2.comPort.param[value].ToString();
|
string option = MainV2.comPort.param[value].ToString();
|
||||||
temp.Text = option;
|
temp.Text = option;
|
||||||
}
|
}
|
||||||
|
if (control[0].GetType() == typeof(NumericUpDown))
|
||||||
|
{
|
||||||
|
NumericUpDown temp = (NumericUpDown)control[0];
|
||||||
|
string option = MainV2.comPort.param[value].ToString();
|
||||||
|
temp.Text = option;
|
||||||
|
}
|
||||||
if (control[0].GetType() == typeof(CheckBox))
|
if (control[0].GetType() == typeof(CheckBox))
|
||||||
{
|
{
|
||||||
CheckBox temp = (CheckBox)control[0];
|
CheckBox temp = (CheckBox)control[0];
|
||||||
@ -670,7 +676,7 @@ namespace ArdupilotMega.Setup
|
|||||||
private void TXT_battcapacity_Validating(object sender, CancelEventArgs e)
|
private void TXT_battcapacity_Validating(object sender, CancelEventArgs e)
|
||||||
{
|
{
|
||||||
float ans = 0;
|
float ans = 0;
|
||||||
e.Cancel = !float.TryParse(TXT_declination.Text, out ans);
|
e.Cancel = !float.TryParse(TXT_battcapacity.Text, out ans);
|
||||||
}
|
}
|
||||||
private void TXT_battcapacity_Validated(object sender, EventArgs e)
|
private void TXT_battcapacity_Validated(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
@ -1209,6 +1215,11 @@ namespace ArdupilotMega.Setup
|
|||||||
MainV2.comPort.setParam("COL_MAX_", int.Parse(COL_MAX_.Text));
|
MainV2.comPort.setParam("COL_MAX_", int.Parse(COL_MAX_.Text));
|
||||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||||
BUT_swash_manual.Text = "Manual";
|
BUT_swash_manual.Text = "Manual";
|
||||||
|
|
||||||
|
COL_MAX_.Enabled = false;
|
||||||
|
COL_MID_.Enabled = false;
|
||||||
|
COL_MIN_.Enabled = false;
|
||||||
|
BUT_0collective.Enabled = false;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
@ -1216,6 +1227,11 @@ namespace ArdupilotMega.Setup
|
|||||||
COL_MIN_.Text = "1500";
|
COL_MIN_.Text = "1500";
|
||||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||||
BUT_swash_manual.Text = "Save";
|
BUT_swash_manual.Text = "Save";
|
||||||
|
|
||||||
|
COL_MAX_.Enabled = true;
|
||||||
|
COL_MID_.Enabled = true;
|
||||||
|
COL_MIN_.Enabled = true;
|
||||||
|
BUT_0collective.Enabled = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Failed to set HSV_MAN"); }
|
catch { MessageBox.Show("Failed to set HSV_MAN"); }
|
||||||
@ -1231,6 +1247,9 @@ namespace ArdupilotMega.Setup
|
|||||||
MainV2.comPort.setParam("HS4_MAX", int.Parse(HS4_MAX.Text));
|
MainV2.comPort.setParam("HS4_MAX", int.Parse(HS4_MAX.Text));
|
||||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||||
BUT_HS4save.Text = "Manual";
|
BUT_HS4save.Text = "Manual";
|
||||||
|
|
||||||
|
HS4_MAX.Enabled = false;
|
||||||
|
HS4_MIN.Enabled = false;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
@ -1238,6 +1257,10 @@ namespace ArdupilotMega.Setup
|
|||||||
HS4_MAX.Text = "1500";
|
HS4_MAX.Text = "1500";
|
||||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||||
BUT_HS4save.Text = "Save";
|
BUT_HS4save.Text = "Save";
|
||||||
|
|
||||||
|
|
||||||
|
HS4_MAX.Enabled = true;
|
||||||
|
HS4_MIN.Enabled = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Failed to set HSV_MAN"); }
|
catch { MessageBox.Show("Failed to set HSV_MAN"); }
|
||||||
|
@ -1563,6 +1563,33 @@
|
|||||||
<data name=">>CHK_enableoptflow.ZOrder" xml:space="preserve">
|
<data name=">>CHK_enableoptflow.ZOrder" xml:space="preserve">
|
||||||
<value>2</value>
|
<value>2</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="pictureBox2.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
|
||||||
|
<value>Zoom</value>
|
||||||
|
</data>
|
||||||
|
<data name="pictureBox2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
|
<value>NoControl</value>
|
||||||
|
</data>
|
||||||
|
<data name="pictureBox2.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>78, 271</value>
|
||||||
|
</data>
|
||||||
|
<data name="pictureBox2.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>75, 75</value>
|
||||||
|
</data>
|
||||||
|
<data name="pictureBox2.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>29</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>pictureBox2.Name" xml:space="preserve">
|
||||||
|
<value>pictureBox2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>pictureBox2.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>pictureBox2.Parent" xml:space="preserve">
|
||||||
|
<value>tabHardware</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>pictureBox2.ZOrder" xml:space="preserve">
|
||||||
|
<value>3</value>
|
||||||
|
</data>
|
||||||
<data name="linkLabelmagdec.AutoSize" type="System.Boolean, mscorlib">
|
<data name="linkLabelmagdec.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</data>
|
</data>
|
||||||
@ -1591,7 +1618,7 @@
|
|||||||
<value>tabHardware</value>
|
<value>tabHardware</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>linkLabelmagdec.ZOrder" xml:space="preserve">
|
<data name=">>linkLabelmagdec.ZOrder" xml:space="preserve">
|
||||||
<value>3</value>
|
<value>4</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label100.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="label100.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1618,7 +1645,7 @@
|
|||||||
<value>tabHardware</value>
|
<value>tabHardware</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>label100.ZOrder" xml:space="preserve">
|
<data name=">>label100.ZOrder" xml:space="preserve">
|
||||||
<value>4</value>
|
<value>5</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="TXT_declination.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="TXT_declination.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>383, 57</value>
|
<value>383, 57</value>
|
||||||
@ -1642,7 +1669,7 @@
|
|||||||
<value>tabHardware</value>
|
<value>tabHardware</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>TXT_declination.ZOrder" xml:space="preserve">
|
<data name=">>TXT_declination.ZOrder" xml:space="preserve">
|
||||||
<value>5</value>
|
<value>6</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_enableairspeed.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="CHK_enableairspeed.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1669,7 +1696,7 @@
|
|||||||
<value>tabHardware</value>
|
<value>tabHardware</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHK_enableairspeed.ZOrder" xml:space="preserve">
|
<data name=">>CHK_enableairspeed.ZOrder" xml:space="preserve">
|
||||||
<value>6</value>
|
<value>7</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_enablesonar.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="CHK_enablesonar.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1696,7 +1723,7 @@
|
|||||||
<value>tabHardware</value>
|
<value>tabHardware</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHK_enablesonar.ZOrder" xml:space="preserve">
|
<data name=">>CHK_enablesonar.ZOrder" xml:space="preserve">
|
||||||
<value>7</value>
|
<value>8</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_enablecompass.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="CHK_enablecompass.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1723,33 +1750,6 @@
|
|||||||
<value>tabHardware</value>
|
<value>tabHardware</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHK_enablecompass.ZOrder" xml:space="preserve">
|
<data name=">>CHK_enablecompass.ZOrder" xml:space="preserve">
|
||||||
<value>8</value>
|
|
||||||
</data>
|
|
||||||
<data name="pictureBox2.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
|
|
||||||
<value>Zoom</value>
|
|
||||||
</data>
|
|
||||||
<data name="pictureBox2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
|
||||||
<value>NoControl</value>
|
|
||||||
</data>
|
|
||||||
<data name="pictureBox2.Location" type="System.Drawing.Point, System.Drawing">
|
|
||||||
<value>78, 271</value>
|
|
||||||
</data>
|
|
||||||
<data name="pictureBox2.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>75, 75</value>
|
|
||||||
</data>
|
|
||||||
<data name="pictureBox2.TabIndex" type="System.Int32, mscorlib">
|
|
||||||
<value>29</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>pictureBox2.Name" xml:space="preserve">
|
|
||||||
<value>pictureBox2</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>pictureBox2.Type" xml:space="preserve">
|
|
||||||
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>pictureBox2.Parent" xml:space="preserve">
|
|
||||||
<value>tabHardware</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>pictureBox2.ZOrder" xml:space="preserve">
|
|
||||||
<value>9</value>
|
<value>9</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="pictureBox4.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
|
<data name="pictureBox4.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
|
||||||
@ -2940,6 +2940,9 @@ will work with hexa's etc</value>
|
|||||||
<data name=">>label24.ZOrder" xml:space="preserve">
|
<data name=">>label24.ZOrder" xml:space="preserve">
|
||||||
<value>0</value>
|
<value>0</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="HS4_MIN.Enabled" type="System.Boolean, mscorlib">
|
||||||
|
<value>False</value>
|
||||||
|
</data>
|
||||||
<data name="HS4_MIN.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="HS4_MIN.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>21, 40</value>
|
<value>21, 40</value>
|
||||||
</data>
|
</data>
|
||||||
@ -2964,6 +2967,9 @@ will work with hexa's etc</value>
|
|||||||
<data name=">>HS4_MIN.ZOrder" xml:space="preserve">
|
<data name=">>HS4_MIN.ZOrder" xml:space="preserve">
|
||||||
<value>1</value>
|
<value>1</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="HS4_MAX.Enabled" type="System.Boolean, mscorlib">
|
||||||
|
<value>False</value>
|
||||||
|
</data>
|
||||||
<data name="HS4_MAX.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="HS4_MAX.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>106, 40</value>
|
<value>106, 40</value>
|
||||||
</data>
|
</data>
|
||||||
@ -3099,6 +3105,9 @@ will work with hexa's etc</value>
|
|||||||
<data name=">>label21.ZOrder" xml:space="preserve">
|
<data name=">>label21.ZOrder" xml:space="preserve">
|
||||||
<value>1</value>
|
<value>1</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="COL_MIN_.Enabled" type="System.Boolean, mscorlib">
|
||||||
|
<value>False</value>
|
||||||
|
</data>
|
||||||
<data name="COL_MIN_.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="COL_MIN_.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>18, 173</value>
|
<value>18, 173</value>
|
||||||
</data>
|
</data>
|
||||||
@ -3123,6 +3132,9 @@ will work with hexa's etc</value>
|
|||||||
<data name=">>COL_MIN_.ZOrder" xml:space="preserve">
|
<data name=">>COL_MIN_.ZOrder" xml:space="preserve">
|
||||||
<value>2</value>
|
<value>2</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="COL_MID_.Enabled" type="System.Boolean, mscorlib">
|
||||||
|
<value>False</value>
|
||||||
|
</data>
|
||||||
<data name="COL_MID_.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="COL_MID_.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>17, 117</value>
|
<value>17, 117</value>
|
||||||
</data>
|
</data>
|
||||||
@ -3147,6 +3159,9 @@ will work with hexa's etc</value>
|
|||||||
<data name=">>COL_MID_.ZOrder" xml:space="preserve">
|
<data name=">>COL_MID_.ZOrder" xml:space="preserve">
|
||||||
<value>3</value>
|
<value>3</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="COL_MAX_.Enabled" type="System.Boolean, mscorlib">
|
||||||
|
<value>False</value>
|
||||||
|
</data>
|
||||||
<data name="COL_MAX_.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="COL_MAX_.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>18, 45</value>
|
<value>18, 45</value>
|
||||||
</data>
|
</data>
|
||||||
@ -3171,6 +3186,9 @@ will work with hexa's etc</value>
|
|||||||
<data name=">>COL_MAX_.ZOrder" xml:space="preserve">
|
<data name=">>COL_MAX_.ZOrder" xml:space="preserve">
|
||||||
<value>4</value>
|
<value>4</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="BUT_0collective.Enabled" type="System.Boolean, mscorlib">
|
||||||
|
<value>False</value>
|
||||||
|
</data>
|
||||||
<data name="BUT_0collective.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_0collective.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
@ -4065,24 +4083,21 @@ will work with hexa's etc</value>
|
|||||||
<data name="$this.ClientSize" type="System.Drawing.Size, System.Drawing">
|
<data name="$this.ClientSize" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>674, 419</value>
|
<value>674, 419</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="$this.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
|
||||||
<value>NoControl</value>
|
|
||||||
</data>
|
|
||||||
<data name="$this.Text" xml:space="preserve">
|
<data name="$this.Text" xml:space="preserve">
|
||||||
<value>APMSetup</value>
|
<value>APMSetup</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>toolTip1.Name" xml:space="preserve">
|
|
||||||
<value>toolTip1</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>toolTip1.Type" xml:space="preserve">
|
|
||||||
<value>System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>currentStateBindingSource.Name" xml:space="preserve">
|
<data name=">>currentStateBindingSource.Name" xml:space="preserve">
|
||||||
<value>currentStateBindingSource</value>
|
<value>currentStateBindingSource</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>currentStateBindingSource.Type" xml:space="preserve">
|
<data name=">>currentStateBindingSource.Type" xml:space="preserve">
|
||||||
<value>System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
<value>System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name=">>toolTip1.Name" xml:space="preserve">
|
||||||
|
<value>toolTip1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>toolTip1.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.ToolTip, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
<data name=">>$this.Name" xml:space="preserve">
|
<data name=">>$this.Name" xml:space="preserve">
|
||||||
<value>Setup</value>
|
<value>Setup</value>
|
||||||
</data>
|
</data>
|
||||||
|
Loading…
Reference in New Issue
Block a user