APM Planner 1.1.25

modify aerosim rc quad hil. tick quad, gains 3000,3000,4000,900
add armed status to HUD
This commit is contained in:
Michael Oborne 2012-01-20 22:50:18 +08:00
parent 52a9bb3cd1
commit cfe33d8b46
6 changed files with 49 additions and 8 deletions

View File

@ -165,6 +165,7 @@ namespace ArdupilotMega
public MainV2.Firmwares firmware = MainV2.Firmwares.ArduPlane;
public float freemem { get; set; }
public float brklevel { get; set; }
public int armed { get; set; }
// stats
public ushort packetdropremote { get; set; }
@ -407,6 +408,8 @@ namespace ArdupilotMega
sysstatus = (ArdupilotMega.MAVLink.__mavlink_sys_status_t)(temp);
armed = sysstatus.status;
string oldmode = mode;
switch (sysstatus.mode)

View File

@ -168,6 +168,7 @@
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("navroll", this.bindingSource1, "nav_roll", true));
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("pitch", this.bindingSource1, "pitch", true));
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("roll", this.bindingSource1, "roll", true));
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("status", this.bindingSource1, "armed", true));
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("targetalt", this.bindingSource1, "targetalt", true));
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("targetheading", this.bindingSource1, "nav_bearing", true));
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("targetspeed", this.bindingSource1, "targetairspeed", true));
@ -192,6 +193,7 @@
this.hud1.opengl = true;
this.hud1.pitch = 0F;
this.hud1.roll = 0F;
this.hud1.status = 0;
this.hud1.streamjpg = null;
this.hud1.targetalt = 0F;
this.hud1.targetheading = 0F;

View File

@ -391,6 +391,8 @@ namespace ArdupilotMega.GCSViews
if (tracklast.AddSeconds(1) < DateTime.Now)
{
gMapControl1.HoldInvalidation = true;
if (trackPoints.Count > int.Parse(MainV2.config["NUM_tracklength"].ToString()))
{
trackPoints.RemoveRange(0, trackPoints.Count - int.Parse(MainV2.config["NUM_tracklength"].ToString()));
@ -410,7 +412,7 @@ namespace ArdupilotMega.GCSViews
FlightPlanner.pointlist.AddRange(MainV2.comPort.wps);
}
gMapControl1.HoldInvalidation = true;
routes.Markers.Clear();
routes.Routes.Clear();

View File

@ -532,7 +532,7 @@ namespace ArdupilotMega.GCSViews
Console.WriteLine("REQ streams - sim");
try
{
if (CHK_quad.Checked)
if (CHK_quad.Checked && !RAD_aerosimrc.Checked)
{
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_CONTROLLER, 0); // request servoout
}
@ -919,7 +919,7 @@ namespace ArdupilotMega.GCSViews
imu.yacc = (Int16)((accel3D.Y + aeroin.Model_fAccelY) * 1000); // roll
imu.zacc = (Int16)((accel3D.Z + aeroin.Model_fAccelZ) * 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);
@ -1076,7 +1076,7 @@ namespace ArdupilotMega.GCSViews
}
// write arduimu to ardupilot
if (CHK_quad.Checked) // quad does its own
if (CHK_quad.Checked && !RAD_aerosimrc.Checked) // quad does its own
{
return;
}
@ -1240,7 +1240,7 @@ namespace ArdupilotMega.GCSViews
bool heli = CHK_heli.Checked;
if (CHK_quad.Checked)
if (CHK_quad.Checked && !RAD_aerosimrc.Checked)
{
double[] m = new double[4];
@ -1255,6 +1255,7 @@ namespace ArdupilotMega.GCSViews
lastfdmdata.latitude = DATA[20][0] * deg2rad;
lastfdmdata.longitude = DATA[20][1] * deg2rad;
lastfdmdata.altitude = (DATA[20][2]);
lastfdmdata.version = 999;
}
try
@ -1281,7 +1282,7 @@ namespace ArdupilotMega.GCSViews
Array.Copy(BitConverter.GetBytes((double)(quad.pitch)), 0, FlightGear, 72, 8);
Array.Copy(BitConverter.GetBytes((double)(quad.yaw)), 0, FlightGear, 80, 8);
if (RAD_softFlightGear.Checked)
if (RAD_softFlightGear.Checked || RAD_softXplanes.Checked)
{
Array.Reverse(FlightGear, 0, 8);
@ -1330,6 +1331,9 @@ namespace ArdupilotMega.GCSViews
pitch_out = (float)MainV2.cs.hilch2 / pitchgain;
throttle_out = ((float)MainV2.cs.hilch3 / 2 + 5000) / throttlegain;
rudder_out = (float)MainV2.cs.hilch4 / ruddergain;
if (RAD_aerosimrc.Checked && CHK_quad.Checked)
throttle_out = (float)(MainV2.cs.hilch3 - 1100) / throttlegain;
}
@ -1403,7 +1407,6 @@ namespace ArdupilotMega.GCSViews
}
catch (Exception e) { Console.WriteLine("Error updateing screen stuff " + e.ToString()); }
packetssent++;
if (RAD_aerosimrc.Checked)
@ -1475,6 +1478,8 @@ namespace ArdupilotMega.GCSViews
if (RAD_softXplanes.Checked)
{
// sending only 1 packet instead of many.
byte[] Xplane = new byte[5 + 36 + 36];

View File

@ -144,6 +144,11 @@ namespace hud
[System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
public DateTime datetime { get { return _datetime; } set { if (_datetime != value) { _datetime = value; this.Invalidate(); } } }
[System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
public int status { get; set; }
int statuslast = 0;
DateTime armedtimer = DateTime.MinValue;
public bool bgon = true;
public bool hudon = true;
@ -739,6 +744,30 @@ namespace hud
graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2);
graphicsObject.RotateTransform(-roll);
// draw armed
if (status != statuslast)
{
armedtimer = DateTime.Now;
}
if (status == 3) // not armed
{
//if ((armedtimer.AddSeconds(8) > DateTime.Now))
{
drawstring(graphicsObject, "DISARMED", font, fontsize + 10, Brushes.Red, -85, halfheight / -3);
statuslast = status;
}
}
else if (status == 4) // armed
{
if ((armedtimer.AddSeconds(8) > DateTime.Now))
{
drawstring(graphicsObject, "ARMED", font, fontsize + 20, Brushes.Red, -70, halfheight / -3);
statuslast = status;
}
}
//draw pitch
int lengthshort = this.Width / 12;

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.24")]
[assembly: AssemblyFileVersion("1.1.25")]
[assembly: NeutralResourcesLanguageAttribute("")]