APM Planner 1.1.32

fix gauge updating
add more checks on add wp - default alt and home alt
fix xplane 10 gps heading - should be 100% working now.
fix xplane throttle issue - from rc library change - rc3_trim should be same as rc3_min
This commit is contained in:
Michael Oborne 2012-02-04 17:59:37 +08:00
parent c95a295fd6
commit 2f57edda06
10 changed files with 161 additions and 115 deletions

View File

@ -221,13 +221,13 @@ namespace AGaugeApp
#region properties
[System.ComponentModel.Browsable(true)]
public Single Value0 { get { return m_value[0]; } set { m_NeedIdx = 0; Value = value; } }
public Single Value0 { get { return m_value[0]; } set { m_NeedIdx = 0; Value = value; this.Invalidate(); } }
[System.ComponentModel.Browsable(true)]
public Single Value1 { get { return m_value[1]; } set { m_NeedIdx = 1; Value = value; } }
public Single Value1 { get { return m_value[1]; } set { m_NeedIdx = 1; Value = value; this.Invalidate(); } }
[System.ComponentModel.Browsable(true)]
public Single Value2 { get { return m_value[2]; } set { m_NeedIdx = 2; Value = value; } }
public Single Value2 { get { return m_value[2]; } set { m_NeedIdx = 2; Value = value; this.Invalidate(); } }
[System.ComponentModel.Browsable(true)]
public Single Value3 { get { return m_value[3]; } set { m_NeedIdx = 3; Value = value; } }
public Single Value3 { get { return m_value[3]; } set { m_NeedIdx = 3; Value = value; this.Invalidate(); } }
[System.ComponentModel.Browsable(true),
System.ComponentModel.Category("AGauge"),

View File

@ -256,7 +256,7 @@ namespace ArdupilotMega
if (ind != -1)
logdata = logdata.Substring(0, ind);
if (messages.Count > 5)
while (messages.Count > 5)
{
messages.RemoveAt(0);
}

View File

@ -191,6 +191,8 @@
this.STB_YAW_P = new System.Windows.Forms.NumericUpDown();
this.label35 = new System.Windows.Forms.Label();
this.groupBox21 = new System.Windows.Forms.GroupBox();
this.STAB_D = new System.Windows.Forms.NumericUpDown();
this.lblSTAB_D = new System.Windows.Forms.Label();
this.STB_PIT_IMAX = new System.Windows.Forms.NumericUpDown();
this.label36 = new System.Windows.Forms.Label();
this.STB_PIT_I = new System.Windows.Forms.NumericUpDown();
@ -283,8 +285,6 @@
this.BUT_load = new ArdupilotMega.MyButton();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.BUT_compare = new ArdupilotMega.MyButton();
this.STAB_D = new System.Windows.Forms.NumericUpDown();
this.lblSTAB_D = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit();
this.ConfigTabs.SuspendLayout();
this.TabAP.SuspendLayout();
@ -371,6 +371,7 @@
((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).BeginInit();
this.groupBox21.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.STAB_D)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).BeginInit();
@ -395,7 +396,6 @@
((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).BeginInit();
this.TabPlanner.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.STAB_D)).BeginInit();
this.SuspendLayout();
//
// Params
@ -1115,6 +1115,7 @@
// TUNE
//
this.TUNE.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
this.TUNE.DropDownWidth = 150;
this.TUNE.FormattingEnabled = true;
this.TUNE.Items.AddRange(new object[] {
resources.GetString("TUNE.Items"),
@ -1149,6 +1150,7 @@
// CH7_OPT
//
this.CH7_OPT.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
this.CH7_OPT.DropDownWidth = 150;
this.CH7_OPT.FormattingEnabled = true;
this.CH7_OPT.Items.AddRange(new object[] {
resources.GetString("CH7_OPT.Items"),
@ -1449,6 +1451,16 @@
this.groupBox21.Name = "groupBox21";
this.groupBox21.TabStop = false;
//
// STAB_D
//
resources.ApplyResources(this.STAB_D, "STAB_D");
this.STAB_D.Name = "STAB_D";
//
// lblSTAB_D
//
resources.ApplyResources(this.lblSTAB_D, "lblSTAB_D");
this.lblSTAB_D.Name = "lblSTAB_D";
//
// STB_PIT_IMAX
//
resources.ApplyResources(this.STB_PIT_IMAX, "STB_PIT_IMAX");
@ -2102,16 +2114,6 @@
this.BUT_compare.UseVisualStyleBackColor = true;
this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click);
//
// STAB_D
//
resources.ApplyResources(this.STAB_D, "STAB_D");
this.STAB_D.Name = "STAB_D";
//
// lblSTAB_D
//
resources.ApplyResources(this.lblSTAB_D, "lblSTAB_D");
this.lblSTAB_D.Name = "lblSTAB_D";
//
// Configuration
//
resources.ApplyResources(this, "$this");
@ -2213,6 +2215,7 @@
((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).EndInit();
this.groupBox21.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.STAB_D)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).EndInit();
@ -2237,7 +2240,6 @@
((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).EndInit();
this.TabPlanner.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.STAB_D)).EndInit();
this.ResumeLayout(false);
}

View File

@ -281,12 +281,20 @@ namespace ArdupilotMega.GCSViews
cell.Value = TXT_DefaultAlt.Text;
float result;
float.TryParse(TXT_homealt.Text, out result);
if (result == 0)
{
MessageBox.Show("You must have a home altitude");
float result;
float.TryParse(TXT_homealt.Text, out result);
if (result == 0)
{
MessageBox.Show("You must have a home altitude");
}
if (!float.TryParse(TXT_DefaultAlt.Text, out result))
{
MessageBox.Show("Your default alt is not valid");
return;
}
}
float ans;
@ -784,7 +792,7 @@ namespace ArdupilotMega.GCSViews
cmd = Commands[Command.Index, selectedrow].Value.ToString();
}
catch { cmd = option; }
Console.WriteLine("editformat " + option + " value " + cmd);
//Console.WriteLine("editformat " + option + " value " + cmd);
ChangeColumnHeader(cmd);
}
catch (Exception ex) { MessageBox.Show(ex.ToString()); }
@ -916,7 +924,7 @@ namespace ArdupilotMega.GCSViews
drawnpolygons.Markers.Add(m);
drawnpolygons.Markers.Add(mBorders);
}
catch (Exception) { }
catch (Exception ex) { Console.WriteLine(ex.ToString()); }
}
/// <summary>
@ -1086,11 +1094,16 @@ namespace ArdupilotMega.GCSViews
else if (home.Length > 5 && usable == 0)
{
lookat = "<LookAt> <longitude>" + TXT_homelng.Text.ToString(new System.Globalization.CultureInfo("en-US")) + "</longitude> <latitude>" + TXT_homelat.Text.ToString(new System.Globalization.CultureInfo("en-US")) + "</latitude> <range>4000</range> </LookAt>";
MainMap.HoldInvalidation = true;
MainMap.ZoomAndCenterMarkers("objects");
MainMap.Zoom -= 2;
RectLatLng? rect = MainMap.GetRectOfAllMarkers("objects");
if (rect.HasValue)
{
MainMap.Position = rect.Value.LocationMiddle;
}
MainMap.Zoom = 17;
MainMap_OnMapZoomChanged();
MainMap.HoldInvalidation = false;
}
RegeneratePolygon();
@ -1933,8 +1946,13 @@ namespace ArdupilotMega.GCSViews
{
if (CurentRectMarker.InnerMarker.Tag.ToString().Contains("grid"))
{
drawnpolygon.Points[int.Parse(CurentRectMarker.InnerMarker.Tag.ToString().Replace("grid", "")) - 1] = new PointLatLng(end.Lat, end.Lng);
MainMap.UpdatePolygonLocalPosition(drawnpolygon);
try
{
drawnpolygon.Points[int.Parse(CurentRectMarker.InnerMarker.Tag.ToString().Replace("grid", "")) - 1] = new PointLatLng(end.Lat, end.Lng);
MainMap.UpdatePolygonLocalPosition(drawnpolygon);
MainMap.Invalidate();
}
catch { }
}
else
{
@ -2002,6 +2020,7 @@ namespace ArdupilotMega.GCSViews
{
drawnpolygon.Points[int.Parse(CurentRectMarker.InnerMarker.Tag.ToString().Replace("grid", "")) - 1] = new PointLatLng(point.Lat, point.Lng);
MainMap.UpdatePolygonLocalPosition(drawnpolygon);
MainMap.Invalidate();
}
}
catch { }
@ -2446,6 +2465,24 @@ namespace ArdupilotMega.GCSViews
string angle = (90).ToString("0");
Common.InputBox("Angle", "Enter the line direction (0-180)", ref angle);
double tryme = 0;
if (!double.TryParse(angle, out tryme))
{
MessageBox.Show("Invalid Angle");
return;
}
if (!double.TryParse(alt, out tryme))
{
MessageBox.Show("Invalid Alt");
return;
}
if (!double.TryParse(distance, out tryme))
{
MessageBox.Show("Invalid Distance");
return;
}
#if DEBUG
//Commands.Rows.Clear();
#endif

View File

@ -83,7 +83,7 @@
this.label17 = new ArdupilotMega.MyLabel();
this.panel5 = new System.Windows.Forms.Panel();
this.zg1 = new ZedGraph.ZedGraphControl();
this.timer1 = new System.Windows.Forms.Timer(this.components);
this.timer_servo_graph = new System.Windows.Forms.Timer(this.components);
this.panel6 = new System.Windows.Forms.Panel();
this.label28 = new ArdupilotMega.MyLabel();
this.label29 = new ArdupilotMega.MyLabel();
@ -501,9 +501,9 @@
this.zg1.ScrollMinY = 0D;
this.zg1.ScrollMinY2 = 0D;
//
// timer1
// timer_servo_graph
//
this.timer1.Tick += new System.EventHandler(this.timer1_Tick);
this.timer_servo_graph.Tick += new System.EventHandler(this.timer1_Tick);
//
// panel6
//
@ -692,7 +692,6 @@
this.RAD_aerosimrc.Name = "RAD_aerosimrc";
this.toolTip1.SetToolTip(this.RAD_aerosimrc, resources.GetString("RAD_aerosimrc.ToolTip"));
this.RAD_aerosimrc.UseVisualStyleBackColor = true;
this.RAD_aerosimrc.CheckedChanged += new System.EventHandler(this.RAD_aerosimrc_CheckedChanged);
//
// RAD_JSBSim
//
@ -700,7 +699,6 @@
this.RAD_JSBSim.Name = "RAD_JSBSim";
this.toolTip1.SetToolTip(this.RAD_JSBSim, resources.GetString("RAD_JSBSim.ToolTip"));
this.RAD_JSBSim.UseVisualStyleBackColor = true;
this.RAD_JSBSim.CheckedChanged += new System.EventHandler(this.RAD_JSBSim_CheckedChanged);
//
// CHK_xplane10
//
@ -811,7 +809,7 @@
private ArdupilotMega.MyLabel label19;
private ArdupilotMega.MyLabel TXT_control_mode;
private ZedGraph.ZedGraphControl zg1;
private System.Windows.Forms.Timer timer1;
private System.Windows.Forms.Timer timer_servo_graph;
private System.Windows.Forms.Panel panel6;
private System.Windows.Forms.TextBox TXT_ruddergain;
private System.Windows.Forms.TextBox TXT_pitchgain;

View File

@ -280,7 +280,7 @@ namespace ArdupilotMega.GCSViews
_procstartinfo.UseShellExecute = true;
//_procstartinfo.RedirectStandardOutput = true;
System.Diagnostics.Process.Start(_procstartinfo);
@ -307,12 +307,12 @@ namespace ArdupilotMega.GCSViews
};
t11.Start();
MainV2.threads.Add(t11);
timer1.Start();
timer_servo_graph.Start();
}
else
{
timer1.Stop();
timer_servo_graph.Stop();
threadrun = 0;
if (SimulatorRECV != null)
SimulatorRECV.Close();
@ -569,7 +569,8 @@ namespace ArdupilotMega.GCSViews
RECVprocess(udpdata, recv, comPort);
}
}
catch { //OutputLog.AppendText("Xplanes Data Problem - You need DATA IN/OUT 3, 4, 17, 18, 19, 20\n" + ex.Message + "\n");
catch
{ //OutputLog.AppendText("Xplanes Data Problem - You need DATA IN/OUT 3, 4, 17, 18, 19, 20\n" + ex.Message + "\n");
}
}
if (MavLink != null && MavLink.Client != null && MavLink.Client.Connected && MavLink.Available > 0)
@ -606,7 +607,7 @@ namespace ArdupilotMega.GCSViews
if (hzcounttime.Second != DateTime.Now.Second)
{
// Console.WriteLine("SIM hz {0}", hzcount);
// Console.WriteLine("SIM hz {0}", hzcount);
hzcount = 0;
hzcounttime = DateTime.Now;
}
@ -675,11 +676,11 @@ namespace ArdupilotMega.GCSViews
MavLink = new UdpClient("127.0.0.1", 14550);
}
float oldax =0, olday =0, oldaz = 0;
float oldax = 0, olday = 0, oldaz = 0;
DateTime oldtime = DateTime.Now;
#if MAVLINK10
ArdupilotMega.MAVLink.__mavlink_gps_raw_int_t oldgps = new MAVLink.__mavlink_gps_raw_int_t();
#endif
#endif
ArdupilotMega.MAVLink.__mavlink_attitude_t oldatt = new ArdupilotMega.MAVLink.__mavlink_attitude_t();
@ -740,7 +741,9 @@ namespace ArdupilotMega.GCSViews
att.pitchspeed = (DATA[17][0]);
att.rollspeed = (DATA[17][1]);
att.yawspeed = (DATA[17][2]);
} else {
}
else
{
att.pitch = (DATA[17][0] * deg2rad);
att.roll = (DATA[17][1] * deg2rad);
att.yaw = (DATA[17][2] * deg2rad);
@ -799,9 +802,9 @@ namespace ArdupilotMega.GCSViews
double head = DATA[18][2] - 90;
#if MAVLINK10
imu.time_usec = ((ulong)DateTime.Now.ToBinary());
#else
imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif
#else
imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif
imu.xgyro = xgyro; // roll - yes
imu.xmag = (short)(Math.Sin(head * deg2rad) * 1000);
imu.ygyro = ygyro; // pitch - yes
@ -817,7 +820,14 @@ namespace ArdupilotMega.GCSViews
#if MAVLINK10
gps.alt = (int)(DATA[20][2] * ft2m * 1000);
gps.fix_type = 3;
gps.cog = (ushort)(DATA[19][2] * 100);
if (xplane9)
{
gps.cog = ((float)DATA[19][2]);
}
else
{
gps.cog = ((float)DATA[18][2]);
}
gps.lat = (int)(DATA[20][0] * 1.0e7);
gps.lon = (int)(DATA[20][1] * 1.0e7);
gps.time_usec = ((ulong)0);
@ -825,7 +835,14 @@ namespace ArdupilotMega.GCSViews
#else
gps.alt = ((float)(DATA[20][2] * ft2m));
gps.fix_type = 3;
gps.hdg = ((float)DATA[19][2]);
if (xplane9)
{
gps.hdg = ((float)DATA[19][2]);
}
else
{
gps.hdg = ((float)DATA[18][2]);
}
gps.lat = ((float)DATA[20][0]);
gps.lon = ((float)DATA[20][1]);
gps.usec = ((ulong)0);
@ -860,9 +877,9 @@ namespace ArdupilotMega.GCSViews
#if MAVLINK10
imu.time_usec = ((ulong)DateTime.Now.ToBinary());
#else
imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif
#else
imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif
imu.xacc = ((Int16)(imudata2.accelX * 9808 / 32.2));
imu.xgyro = ((Int16)(imudata2.rateRoll * 17.453293));
@ -873,7 +890,7 @@ namespace ArdupilotMega.GCSViews
imu.zacc = ((Int16)(imudata2.accelZ * 9808 / 32.2)); // + 1000
imu.zgyro = ((Int16)(imudata2.rateYaw * 17.453293));
imu.zmag = 0;
#if MAVLINK10
gps.alt = ((int)(imudata2.altitude * ft2m * 1000));
gps.fix_type = 3;
@ -927,9 +944,9 @@ namespace ArdupilotMega.GCSViews
#if MAVLINK10
imu.time_usec = ((ulong)DateTime.Now.ToBinary());
#else
imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif
#else
imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif
imu.xgyro = (short)(aeroin.Model_fAngVel_Body_X * 1000); // roll - yes
//imu.xmag = (short)(Math.Sin(head * deg2rad) * 1000);
imu.ygyro = (short)(aeroin.Model_fAngVel_Body_Y * 1000); // pitch - yes
@ -943,7 +960,7 @@ namespace ArdupilotMega.GCSViews
imu.yacc = (Int16)((accel3D.Y + aeroin.Model_fAccel_Body_Y) * 1000); // roll
imu.zacc = (Int16)((accel3D.Z + aeroin.Model_fAccel_Body_Z) * 1000);
// Console.WriteLine("x {0} y {1} z {2}", imu.xacc, imu.yacc, imu.zacc);
// Console.WriteLine("x {0} y {1} z {2}", imu.xacc, imu.yacc, imu.zacc);
#if MAVLINK10
gps.alt = ((int)(aeroin.Model_fPosZ) * 1000);
@ -953,7 +970,7 @@ namespace ArdupilotMega.GCSViews
gps.lon = (int)(aeroin.Model_fLongitude * 1.0e7);
gps.time_usec = ((ulong)DateTime.Now.Ticks);
gps.vel = (ushort)(Math.Sqrt((aeroin.Model_fVelY * aeroin.Model_fVelY) + (aeroin.Model_fVelX * aeroin.Model_fVelX)) * 100);
#else
#else
gps.alt = ((float)(aeroin.Model_fPosZ));
gps.fix_type = 3;
gps.hdg = ((float)Math.Atan2(aeroin.Model_fVelX, aeroin.Model_fVelY) * rad2deg);
@ -988,9 +1005,9 @@ namespace ArdupilotMega.GCSViews
#if MAVLINK10
imu.time_usec = ((ulong)DateTime.Now.ToBinary());
#else
imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif
#else
imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif
imu.xgyro = (short)(fdm.phidot); // roll - yes
//imu.xmag = (short)(Math.Sin(head * deg2rad) * 1000);
imu.ygyro = (short)(fdm.thetadot); // pitch - yes
@ -1134,10 +1151,10 @@ namespace ArdupilotMega.GCSViews
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.psi * rad2deg), 0, sitlout, a += 8, 8);
Array.Copy(BitConverter.GetBytes((double)lastfdmdata.vcas * ft2m), 0, sitlout, a += 8, 8);
// Console.WriteLine(lastfdmdata.theta);
// Console.WriteLine(lastfdmdata.theta);
Array.Copy(BitConverter.GetBytes((int)0x4c56414e), 0, sitlout, a += 8, 4);
SITLSEND.Send(sitlout, sitlout.Length);
return;
@ -1176,27 +1193,27 @@ namespace ArdupilotMega.GCSViews
comPort.sendPacket(asp);
#else
#else
if (chkSensor.Checked == false) // attitude
{
comPort.sendPacket( att);
comPort.sendPacket(att);
comPort.sendPacket( asp);
comPort.sendPacket(asp);
}
else // raw imu
{
// imudata
comPort.sendPacket( imu);
comPort.sendPacket(imu);
#endif
#endif
MAVLink.__mavlink_raw_pressure_t pres = new MAVLink.__mavlink_raw_pressure_t();
double calc = (101325 * Math.Pow(1 - 2.25577 * Math.Pow(10, -5) * gps.alt, 5.25588)); // updated from valid gps
pres.press_diff1 = (short)(int)(calc - 101325); // 0 alt is 0 pa
MAVLink.__mavlink_raw_pressure_t pres = new MAVLink.__mavlink_raw_pressure_t();
double calc = (101325 * Math.Pow(1 - 2.25577 * Math.Pow(10, -5) * gps.alt, 5.25588)); // updated from valid gps
pres.press_diff1 = (short)(int)(calc - 101325); // 0 alt is 0 pa
comPort.sendPacket(pres);
comPort.sendPacket(pres);
#if !MAVLINK10
comPort.sendPacket(asp);
}
@ -1210,7 +1227,7 @@ namespace ArdupilotMega.GCSViews
comPort.sendPacket(gps);
}
#endif
}
}
HIL.QuadCopter quad = new HIL.QuadCopter();
@ -1228,7 +1245,7 @@ namespace ArdupilotMega.GCSViews
/// <param name="pitch_out">-1 to 1</param>
/// <param name="rudder_out">-1 to 1</param>
/// <param name="throttle_out">0 to 1</param>
private void updateScreenDisplay(double lat,double lng,double alt,double roll,double pitch,double heading, double yaw,double roll_out,double pitch_out, double rudder_out, double throttle_out)
private void updateScreenDisplay(double lat, double lng, double alt, double roll, double pitch, double heading, double yaw, double roll_out, double pitch_out, double rudder_out, double throttle_out)
{
try
{
@ -1329,7 +1346,7 @@ namespace ArdupilotMega.GCSViews
}
catch (Exception) { Console.WriteLine("Socket Write failed, FG closed?"); }
updateScreenDisplay(lastfdmdata.latitude,lastfdmdata.longitude,lastfdmdata.altitude * .3048,lastfdmdata.phi,lastfdmdata.theta,lastfdmdata.psi,lastfdmdata.psi,m[0],m[1],m[2],m[3]);
updateScreenDisplay(lastfdmdata.latitude, lastfdmdata.longitude, lastfdmdata.altitude * .3048, lastfdmdata.phi, lastfdmdata.theta, lastfdmdata.psi, lastfdmdata.psi, m[0], m[1], m[2], m[3]);
return;
@ -1350,10 +1367,9 @@ namespace ArdupilotMega.GCSViews
}
else
{
roll_out = (float)MainV2.cs.hilch1 / rollgain;
pitch_out = (float)MainV2.cs.hilch2 / pitchgain;
throttle_out = ((float)MainV2.cs.hilch3 / 2 + 5000) / throttlegain;
throttle_out = ((float)MainV2.cs.hilch3) / throttlegain;
rudder_out = (float)MainV2.cs.hilch4 / ruddergain;
if (RAD_aerosimrc.Checked && CHK_quad.Checked)
@ -1415,7 +1431,9 @@ namespace ArdupilotMega.GCSViews
if (xplane9)
{
updateScreenDisplay(DATA[20][0] * deg2rad, DATA[20][1] * deg2rad, DATA[20][2] * .3048, DATA[18][1] * deg2rad, DATA[18][0] * deg2rad, DATA[19][2] * deg2rad, DATA[18][2] * deg2rad, roll_out, pitch_out, rudder_out, throttle_out);
} else {
}
else
{
updateScreenDisplay(DATA[20][0] * deg2rad, DATA[20][1] * deg2rad, DATA[20][2] * .3048, DATA[17][1] * deg2rad, DATA[17][0] * deg2rad, DATA[18][2] * deg2rad, DATA[17][2] * deg2rad, roll_out, pitch_out, rudder_out, throttle_out);
}
@ -1444,7 +1462,7 @@ namespace ArdupilotMega.GCSViews
Array.Copy(BitConverter.GetBytes((double)(roll_out * REV_roll)), 0, AeroSimRC, 0, 8);
Array.Copy(BitConverter.GetBytes((double)(pitch_out * REV_pitch * -1)), 0, AeroSimRC, 8, 8);
Array.Copy(BitConverter.GetBytes((double)(rudder_out * REV_rudder)), 0, AeroSimRC, 16, 8);
Array.Copy(BitConverter.GetBytes((double)((throttle_out *2) -1)), 0, AeroSimRC, 24, 8);
Array.Copy(BitConverter.GetBytes((double)((throttle_out * 2) - 1)), 0, AeroSimRC, 24, 8);
if (heli)
{
@ -1487,12 +1505,12 @@ namespace ArdupilotMega.GCSViews
if (RAD_JSBSim.Checked)
{
roll_out = Constrain(roll_out * REV_roll, -1f, 1f);
pitch_out = Constrain(-pitch_out * REV_pitch, -1f,1f);
pitch_out = Constrain(-pitch_out * REV_pitch, -1f, 1f);
rudder_out = Constrain(rudder_out * REV_rudder, -1f, 1f);
throttle_out = Constrain(throttle_out, -0.0f, 1f);
string cmd = string.Format("set fcs/aileron-cmd-norm {0}\r\nset fcs/elevator-cmd-norm {1}\r\nset fcs/rudder-cmd-norm {2}\r\nset fcs/throttle-cmd-norm {3}\r\n",roll_out,pitch_out,rudder_out,throttle_out);
string cmd = string.Format("set fcs/aileron-cmd-norm {0}\r\nset fcs/elevator-cmd-norm {1}\r\nset fcs/rudder-cmd-norm {2}\r\nset fcs/throttle-cmd-norm {3}\r\n", roll_out, pitch_out, rudder_out, throttle_out);
//Console.Write(cmd);
byte[] data = System.Text.Encoding.ASCII.GetBytes(cmd);
@ -1529,7 +1547,7 @@ namespace ArdupilotMega.GCSViews
if (RAD_softXplanes.Checked)
{
// sending only 1 packet instead of many.
@ -1736,9 +1754,9 @@ namespace ArdupilotMega.GCSViews
//myPane.Chart.Fill = new Fill(Color.White, Color.LightGray, 45.0f);
// Sample at 50ms intervals
timer1.Interval = 50;
timer1.Enabled = true;
timer1.Start();
timer_servo_graph.Interval = 50;
timer_servo_graph.Enabled = true;
timer_servo_graph.Start();
// Calculate the Axis Scale Ranges
@ -1778,14 +1796,14 @@ namespace ArdupilotMega.GCSViews
xScale.Max = time + xScale.MajorStep;
xScale.Min = xScale.Max - 30.0;
}
// Make sure the Y axis is rescaled to accommodate actual data
try
{
zg1.AxisChange();
}
catch { }
// Force a redraw
zg1.Invalidate();
// Make sure the Y axis is rescaled to accommodate actual data
try
{
zg1.AxisChange();
}
catch { }
// Force a redraw
zg1.Invalidate();
}
private void SaveSettings_Click(object sender, EventArgs e)
@ -1965,9 +1983,9 @@ namespace ArdupilotMega.GCSViews
if (!MainV2.MONO)
{
extra = " --fg-root=\"" + Path.GetDirectoryName(ofd.FileName.ToLower().Replace("bin\\win32\\","")) + "\\data\"";
extra = " --fg-root=\"" + Path.GetDirectoryName(ofd.FileName.ToLower().Replace("bin\\win32\\", "")) + "\\data\"";
}
System.Diagnostics.Process P = new System.Diagnostics.Process();
P.StartInfo.FileName = ofd.FileName;
P.StartInfo.Arguments = extra + @" --geometry=400x300 --native-fdm=socket,out,50,127.0.0.1,49005,udp --generic=socket,in,50,127.0.0.1,49000,udp,MAVLink --roll=0 --pitch=0 --wind=0@0 --turbulence=0.0 --prop:/sim/frame-rate-throttle-hz=30 --timeofday=noon --shading-flat --fog-disable --disable-specular-highlight --disable-skyblend --disable-random-objects --disable-panel --disable-horizon-effect --disable-clouds --disable-anti-alias-hud ";
@ -2044,7 +2062,7 @@ namespace ArdupilotMega.GCSViews
if (displayfull)
{
//this.Width = 651;
timer1.Start();
timer_servo_graph.Start();
zg1.Visible = true;
@ -2059,7 +2077,7 @@ namespace ArdupilotMega.GCSViews
//this.Width = 651;
//this.Height = 457;
timer1.Stop();
timer_servo_graph.Stop();
zg1.Visible = false;
CHKgraphpitch.Visible = false;
@ -2069,14 +2087,5 @@ namespace ArdupilotMega.GCSViews
}
}
private void RAD_aerosimrc_CheckedChanged(object sender, EventArgs e)
{
}
private void RAD_JSBSim_CheckedChanged(object sender, EventArgs e)
{
}
}
}

View File

@ -1356,7 +1356,7 @@
<data name="&gt;&gt;zg1.ZOrder" xml:space="preserve">
<value>17</value>
</data>
<metadata name="timer1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<metadata name="timer_servo_graph.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>17, 17</value>
</metadata>
<data name="label28.Location" type="System.Drawing.Point, System.Drawing">
@ -2142,10 +2142,10 @@
<data name="&gt;&gt;currentStateBindingSource.Type" xml:space="preserve">
<value>System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;timer1.Name" xml:space="preserve">
<value>timer1</value>
<data name="&gt;&gt;timer_servo_graph.Name" xml:space="preserve">
<value>timer_servo_graph</value>
</data>
<data name="&gt;&gt;timer1.Type" xml:space="preserve">
<data name="&gt;&gt;timer_servo_graph.Type" xml:space="preserve">
<value>System.Windows.Forms.Timer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;toolTip1.Name" xml:space="preserve">

View File

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

View File

@ -220,7 +220,7 @@ namespace ArdupilotMega.Setup
}
}
MessageBox.Show("Ensure all your sticks are centered, and click ok to continue");
MessageBox.Show("Ensure all your sticks are centered and throttle is down, and click ok to continue");
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);