This commit is contained in:
Jason Short 2011-10-28 21:29:18 -07:00
commit be3843ccb9
57 changed files with 3922 additions and 4605 deletions

View File

@ -82,7 +82,7 @@ static void init_ardupilot()
#endif #endif
Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE
"\n\nFree RAM: %lu\n"), "\n\nFree RAM: %u\n"),
memcheck_available_memory()); memcheck_available_memory());

View File

@ -650,7 +650,7 @@ static void Log_Read(int start_page, int end_page)
Serial.printf_P(PSTR((AIRFRAME_NAME) Serial.printf_P(PSTR((AIRFRAME_NAME)
#endif #endif
Serial.printf_P(PSTR("\n" THISFIRMWARE Serial.printf_P(PSTR("\n" THISFIRMWARE
"\nFree RAM: %lu\n"), "\nFree RAM: %u\n"),
memcheck_available_memory()); memcheck_available_memory());
DataFlash.StartRead(start_page); DataFlash.StartRead(start_page);

View File

@ -79,7 +79,7 @@ static void init_ardupilot()
Serial1.begin(38400, 128, 16); Serial1.begin(38400, 128, 16);
Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE
"\n\nFree RAM: %lu\n"), "\n\nFree RAM: %u\n"),
memcheck_available_memory()); memcheck_available_memory());
// //

View File

@ -75,8 +75,14 @@ namespace System.IO.Ports
string dest = Port; string dest = Port;
string host = "127.0.0.1"; string host = "127.0.0.1";
ArdupilotMega.Common.InputBox("remote host", "Enter host name/ip (ensure remote end is already started)", ref host); if (Windows.Forms.DialogResult.Cancel == ArdupilotMega.Common.InputBox("remote host", "Enter host name/ip (ensure remote end is already started)", ref host))
ArdupilotMega.Common.InputBox("remote Port", "Enter remote port", ref dest); {
return;
}
if (Windows.Forms.DialogResult.Cancel == ArdupilotMega.Common.InputBox("remote Port", "Enter remote port", ref dest))
{
return;
}
Port = dest; Port = dest;
client = new TcpClient(host, int.Parse(Port)); client = new TcpClient(host, int.Parse(Port));
@ -169,7 +175,7 @@ namespace System.IO.Ports
VerifyConnected(); VerifyConnected();
int size = client.Available; int size = client.Available;
byte[] crap = new byte[size]; byte[] crap = new byte[size];
Console.WriteLine("UdpSerial DiscardInBuffer {0}",size); Console.WriteLine("TcpSerial DiscardInBuffer {0}",size);
Read(crap, 0, size); Read(crap, 0, size);
} }

View File

@ -193,12 +193,12 @@ namespace ArdupilotMega
{ {
UpdateCurrentSettings(bs, false, MainV2.comPort); UpdateCurrentSettings(bs, false, MainV2.comPort);
} }
/*
public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs, bool updatenow) public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs, bool updatenow)
{ {
UpdateCurrentSettings(bs, false, MainV2.comPort); UpdateCurrentSettings(bs, false, MainV2.comPort);
} }
*/
public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs, bool updatenow, MAVLink mavinterface) public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs, bool updatenow, MAVLink mavinterface)
{ {
if (DateTime.Now > lastupdate.AddMilliseconds(19) || updatenow) // 50 hz if (DateTime.Now > lastupdate.AddMilliseconds(19) || updatenow) // 50 hz

View File

@ -142,6 +142,7 @@
this.label52 = new System.Windows.Forms.Label(); this.label52 = new System.Windows.Forms.Label();
this.TabAC2 = new System.Windows.Forms.TabPage(); this.TabAC2 = new System.Windows.Forms.TabPage();
this.groupBox5 = new System.Windows.Forms.GroupBox(); this.groupBox5 = new System.Windows.Forms.GroupBox();
this.label14 = new System.Windows.Forms.Label();
this.THR_RATE_IMAX = new System.Windows.Forms.DomainUpDown(); this.THR_RATE_IMAX = new System.Windows.Forms.DomainUpDown();
this.THR_RATE_I = new System.Windows.Forms.DomainUpDown(); this.THR_RATE_I = new System.Windows.Forms.DomainUpDown();
this.label20 = new System.Windows.Forms.Label(); this.label20 = new System.Windows.Forms.Label();
@ -223,6 +224,7 @@
this.RATE_RLL_P = new System.Windows.Forms.DomainUpDown(); this.RATE_RLL_P = new System.Windows.Forms.DomainUpDown();
this.label91 = new System.Windows.Forms.Label(); this.label91 = new System.Windows.Forms.Label();
this.TabPlanner = new System.Windows.Forms.TabPage(); this.TabPlanner = new System.Windows.Forms.TabPage();
this.label26 = new System.Windows.Forms.Label();
this.CMB_videoresolutions = new System.Windows.Forms.ComboBox(); this.CMB_videoresolutions = new System.Windows.Forms.ComboBox();
this.label12 = new System.Windows.Forms.Label(); this.label12 = new System.Windows.Forms.Label();
this.CHK_GDIPlus = new System.Windows.Forms.CheckBox(); this.CHK_GDIPlus = new System.Windows.Forms.CheckBox();
@ -273,8 +275,20 @@
this.BUT_load = new ArdupilotMega.MyButton(); this.BUT_load = new ArdupilotMega.MyButton();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.BUT_compare = new ArdupilotMega.MyButton(); this.BUT_compare = new ArdupilotMega.MyButton();
this.label14 = new System.Windows.Forms.Label(); this.groupBox17 = new System.Windows.Forms.GroupBox();
this.label26 = new System.Windows.Forms.Label(); this.ACRO_PIT_IMAX = new System.Windows.Forms.DomainUpDown();
this.label27 = new System.Windows.Forms.Label();
this.ACRO_PIT_I = new System.Windows.Forms.DomainUpDown();
this.label29 = new System.Windows.Forms.Label();
this.ACRO_PIT_P = new System.Windows.Forms.DomainUpDown();
this.label33 = new System.Windows.Forms.Label();
this.groupBox18 = new System.Windows.Forms.GroupBox();
this.ACRO_RLL_IMAX = new System.Windows.Forms.DomainUpDown();
this.label40 = new System.Windows.Forms.Label();
this.ACRO_RLL_I = new System.Windows.Forms.DomainUpDown();
this.label44 = new System.Windows.Forms.Label();
this.ACRO_RLL_P = new System.Windows.Forms.DomainUpDown();
this.label48 = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit();
this.ConfigTabs.SuspendLayout(); this.ConfigTabs.SuspendLayout();
this.TabAPM2.SuspendLayout(); this.TabAPM2.SuspendLayout();
@ -304,6 +318,8 @@
this.groupBox25.SuspendLayout(); this.groupBox25.SuspendLayout();
this.TabPlanner.SuspendLayout(); this.TabPlanner.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).BeginInit();
this.groupBox17.SuspendLayout();
this.groupBox18.SuspendLayout();
this.SuspendLayout(); this.SuspendLayout();
// //
// Params // Params
@ -995,7 +1011,9 @@
// //
// TabAC2 // TabAC2
// //
this.TabAC2.Controls.Add(this.groupBox17);
this.TabAC2.Controls.Add(this.groupBox5); this.TabAC2.Controls.Add(this.groupBox5);
this.TabAC2.Controls.Add(this.groupBox18);
this.TabAC2.Controls.Add(this.CHK_lockrollpitch); this.TabAC2.Controls.Add(this.CHK_lockrollpitch);
this.TabAC2.Controls.Add(this.groupBox4); this.TabAC2.Controls.Add(this.groupBox4);
this.TabAC2.Controls.Add(this.groupBox6); this.TabAC2.Controls.Add(this.groupBox6);
@ -1022,6 +1040,11 @@
this.groupBox5.Name = "groupBox5"; this.groupBox5.Name = "groupBox5";
this.groupBox5.TabStop = false; this.groupBox5.TabStop = false;
// //
// label14
//
resources.ApplyResources(this.label14, "label14");
this.label14.Name = "label14";
//
// THR_RATE_IMAX // THR_RATE_IMAX
// //
resources.ApplyResources(this.THR_RATE_IMAX, "THR_RATE_IMAX"); resources.ApplyResources(this.THR_RATE_IMAX, "THR_RATE_IMAX");
@ -1050,8 +1073,11 @@
// CHK_lockrollpitch // CHK_lockrollpitch
// //
resources.ApplyResources(this.CHK_lockrollpitch, "CHK_lockrollpitch"); resources.ApplyResources(this.CHK_lockrollpitch, "CHK_lockrollpitch");
this.CHK_lockrollpitch.Checked = true;
this.CHK_lockrollpitch.CheckState = System.Windows.Forms.CheckState.Checked;
this.CHK_lockrollpitch.Name = "CHK_lockrollpitch"; this.CHK_lockrollpitch.Name = "CHK_lockrollpitch";
this.CHK_lockrollpitch.UseVisualStyleBackColor = true; this.CHK_lockrollpitch.UseVisualStyleBackColor = true;
this.CHK_lockrollpitch.CheckedChanged += new System.EventHandler(this.CHK_lockrollpitch_CheckedChanged);
// //
// groupBox4 // groupBox4
// //
@ -1545,6 +1571,11 @@
resources.ApplyResources(this.TabPlanner, "TabPlanner"); resources.ApplyResources(this.TabPlanner, "TabPlanner");
this.TabPlanner.Name = "TabPlanner"; this.TabPlanner.Name = "TabPlanner";
// //
// label26
//
resources.ApplyResources(this.label26, "label26");
this.label26.Name = "label26";
//
// CMB_videoresolutions // CMB_videoresolutions
// //
this.CMB_videoresolutions.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList; this.CMB_videoresolutions.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
@ -1911,15 +1942,89 @@
this.BUT_compare.UseVisualStyleBackColor = true; this.BUT_compare.UseVisualStyleBackColor = true;
this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click); this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click);
// //
// label14 // groupBox17
// //
resources.ApplyResources(this.label14, "label14"); this.groupBox17.Controls.Add(this.ACRO_PIT_IMAX);
this.label14.Name = "label14"; this.groupBox17.Controls.Add(this.label27);
this.groupBox17.Controls.Add(this.ACRO_PIT_I);
this.groupBox17.Controls.Add(this.label29);
this.groupBox17.Controls.Add(this.ACRO_PIT_P);
this.groupBox17.Controls.Add(this.label33);
resources.ApplyResources(this.groupBox17, "groupBox17");
this.groupBox17.Name = "groupBox17";
this.groupBox17.TabStop = false;
// //
// label26 // ACRO_PIT_IMAX
// //
resources.ApplyResources(this.label26, "label26"); resources.ApplyResources(this.ACRO_PIT_IMAX, "ACRO_PIT_IMAX");
this.label26.Name = "label26"; this.ACRO_PIT_IMAX.Name = "ACRO_PIT_IMAX";
//
// label27
//
resources.ApplyResources(this.label27, "label27");
this.label27.Name = "label27";
//
// ACRO_PIT_I
//
resources.ApplyResources(this.ACRO_PIT_I, "ACRO_PIT_I");
this.ACRO_PIT_I.Name = "ACRO_PIT_I";
//
// label29
//
resources.ApplyResources(this.label29, "label29");
this.label29.Name = "label29";
//
// ACRO_PIT_P
//
resources.ApplyResources(this.ACRO_PIT_P, "ACRO_PIT_P");
this.ACRO_PIT_P.Name = "ACRO_PIT_P";
//
// label33
//
resources.ApplyResources(this.label33, "label33");
this.label33.Name = "label33";
//
// groupBox18
//
this.groupBox18.Controls.Add(this.ACRO_RLL_IMAX);
this.groupBox18.Controls.Add(this.label40);
this.groupBox18.Controls.Add(this.ACRO_RLL_I);
this.groupBox18.Controls.Add(this.label44);
this.groupBox18.Controls.Add(this.ACRO_RLL_P);
this.groupBox18.Controls.Add(this.label48);
resources.ApplyResources(this.groupBox18, "groupBox18");
this.groupBox18.Name = "groupBox18";
this.groupBox18.TabStop = false;
//
// ACRO_RLL_IMAX
//
resources.ApplyResources(this.ACRO_RLL_IMAX, "ACRO_RLL_IMAX");
this.ACRO_RLL_IMAX.Name = "ACRO_RLL_IMAX";
//
// label40
//
resources.ApplyResources(this.label40, "label40");
this.label40.Name = "label40";
//
// ACRO_RLL_I
//
resources.ApplyResources(this.ACRO_RLL_I, "ACRO_RLL_I");
this.ACRO_RLL_I.Name = "ACRO_RLL_I";
//
// label44
//
resources.ApplyResources(this.label44, "label44");
this.label44.Name = "label44";
//
// ACRO_RLL_P
//
resources.ApplyResources(this.ACRO_RLL_P, "ACRO_RLL_P");
this.ACRO_RLL_P.Name = "ACRO_RLL_P";
//
// label48
//
resources.ApplyResources(this.label48, "label48");
this.label48.Name = "label48";
// //
// Configuration // Configuration
// //
@ -1965,6 +2070,8 @@
this.groupBox25.ResumeLayout(false); this.groupBox25.ResumeLayout(false);
this.TabPlanner.ResumeLayout(false); this.TabPlanner.ResumeLayout(false);
((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).EndInit();
this.groupBox17.ResumeLayout(false);
this.groupBox18.ResumeLayout(false);
this.ResumeLayout(false); this.ResumeLayout(false);
} }
@ -2214,5 +2321,19 @@
private System.Windows.Forms.Label label109; private System.Windows.Forms.Label label109;
private System.Windows.Forms.Label label14; private System.Windows.Forms.Label label14;
private System.Windows.Forms.Label label26; private System.Windows.Forms.Label label26;
private System.Windows.Forms.GroupBox groupBox17;
private System.Windows.Forms.DomainUpDown ACRO_PIT_IMAX;
private System.Windows.Forms.Label label27;
private System.Windows.Forms.DomainUpDown ACRO_PIT_I;
private System.Windows.Forms.Label label29;
private System.Windows.Forms.DomainUpDown ACRO_PIT_P;
private System.Windows.Forms.Label label33;
private System.Windows.Forms.GroupBox groupBox18;
private System.Windows.Forms.DomainUpDown ACRO_RLL_IMAX;
private System.Windows.Forms.Label label40;
private System.Windows.Forms.DomainUpDown ACRO_RLL_I;
private System.Windows.Forms.Label label44;
private System.Windows.Forms.DomainUpDown ACRO_RLL_P;
private System.Windows.Forms.Label label48;
} }
} }

View File

@ -61,24 +61,6 @@ namespace ArdupilotMega.GCSViews
{ {
InitializeComponent(); InitializeComponent();
// fix for dup name
XTRK_ANGLE_CD1.Name = "XTRK_ANGLE_CD";
}
private void Configuration_Load(object sender, EventArgs e)
{
// read tooltips
if (tooltips.Count == 0)
readToolTips();
this.SuspendLayout();
// prefill all fields
param = MainV2.comPort.param;
processToScreen();
this.ResumeLayout();
// enable disable relevbant hardware tabs // enable disable relevbant hardware tabs
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane) if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
{ {
@ -93,6 +75,20 @@ namespace ArdupilotMega.GCSViews
TabAC2.Enabled = true; TabAC2.Enabled = true;
} }
// read tooltips
if (tooltips.Count == 0)
readToolTips();
// prefill all fields
param = MainV2.comPort.param;
processToScreen();
// fix for dup name
XTRK_ANGLE_CD1.Name = "XTRK_ANGLE_CD";
}
private void Configuration_Load(object sender, EventArgs e)
{
// setup up camera button states // setup up camera button states
if (MainV2.cam != null) if (MainV2.cam != null)
{ {
@ -386,7 +382,7 @@ namespace ArdupilotMega.GCSViews
// enable roll and pitch pairing for ac2 // enable roll and pitch pairing for ac2
if (CHK_lockrollpitch.Checked) if (CHK_lockrollpitch.Checked)
{ {
if (name.StartsWith("RATE_") || name.StartsWith("STB_")) if (name.StartsWith("RATE_") || name.StartsWith("STB_") || name.StartsWith("ACRO_"))
{ {
if (name.Contains("_RLL_")) if (name.Contains("_RLL_"))
{ {
@ -534,6 +530,8 @@ namespace ArdupilotMega.GCSViews
continue; continue;
if (name == "WP_TOTAL") if (name == "WP_TOTAL")
continue; continue;
if (name == "CMD_TOTAL")
continue;
if (row.Cells[0].Value.ToString() == name) if (row.Cells[0].Value.ToString() == name)
{ {
if (row.Cells[1].Value.ToString() != value.ToString()) if (row.Cells[1].Value.ToString() != value.ToString())
@ -1021,6 +1019,8 @@ namespace ArdupilotMega.GCSViews
continue; continue;
if (name == "WP_TOTAL") if (name == "WP_TOTAL")
continue; continue;
if (name == "CMD_TOTAL")
continue;
param2[name] = value; param2[name] = value;
} }
@ -1039,5 +1039,10 @@ namespace ArdupilotMega.GCSViews
MessageBox.Show("You need to restart the planner for this to take effect"); MessageBox.Show("You need to restart the planner for this to take effect");
MainV2.config["CHK_GDIPlus"] = CHK_GDIPlus.Checked.ToString(); MainV2.config["CHK_GDIPlus"] = CHK_GDIPlus.Checked.ToString();
} }
private void CHK_lockrollpitch_CheckedChanged(object sender, EventArgs e)
{
}
} }
} }

File diff suppressed because it is too large Load Diff

View File

@ -488,7 +488,13 @@ namespace ArdupilotMega.GCSViews
return; return;
} }
int apmformat_version = ArduinoDetect.decodeApVar(MainV2.comportname, board); int apmformat_version = -1; // fail continue
try
{
apmformat_version = ArduinoDetect.decodeApVar(MainV2.comportname, board);
}
catch { }
if (apmformat_version != -1 && apmformat_version != temp.k_format_version) if (apmformat_version != -1 && apmformat_version != temp.k_format_version)
{ {
@ -678,7 +684,7 @@ namespace ArdupilotMega.GCSViews
Application.DoEvents(); Application.DoEvents();
System.Threading.Thread.Sleep(5000); // 5 seconds - new apvar erases eeprom on new format version, this should buy us some time. System.Threading.Thread.Sleep(10000); // 10 seconds - new apvar erases eeprom on new format version, this should buy us some time.
} }
catch (Exception ex) { lbl_status.Text = "Failed upload"; MessageBox.Show("Check port settings or Port in use? " + ex.ToString()); port.Close(); } catch (Exception ex) { lbl_status.Text = "Failed upload"; MessageBox.Show("Check port settings or Port in use? " + ex.ToString()); port.Close(); }

View File

@ -364,7 +364,7 @@ namespace ArdupilotMega.GCSViews
if (CB_tuning.Checked == false) // draw if in view // if (CB_tuning.Checked == false) // draw if in view
{ {
if (MainV2.comPort.logreadmode && MainV2.comPort.logplaybackfile != null) if (MainV2.comPort.logreadmode && MainV2.comPort.logplaybackfile != null)
@ -992,9 +992,9 @@ namespace ArdupilotMega.GCSViews
CMB_setwp.Items.Add("0 (Home)"); CMB_setwp.Items.Add("0 (Home)");
if (MainV2.comPort.param["WP_TOTAL"] != null) if (MainV2.comPort.param["CMD_TOTAL"] != null)
{ {
int wps = int.Parse(MainV2.comPort.param["WP_TOTAL"].ToString()); int wps = int.Parse(MainV2.comPort.param["CMD_TOTAL"].ToString());
for (int z = 1; z <= wps; z++) for (int z = 1; z <= wps; z++)
{ {
CMB_setwp.Items.Add(z.ToString()); CMB_setwp.Items.Add(z.ToString());

View File

@ -1573,7 +1573,6 @@ namespace ArdupilotMega.GCSViews
xScale.Max = time + xScale.MajorStep; xScale.Max = time + xScale.MajorStep;
xScale.Min = xScale.Max - 30.0; xScale.Min = xScale.Max - 30.0;
} }
// Make sure the Y axis is rescaled to accommodate actual data // Make sure the Y axis is rescaled to accommodate actual data
try try
{ {
@ -1582,7 +1581,6 @@ namespace ArdupilotMega.GCSViews
catch { } catch { }
// Force a redraw // Force a redraw
zg1.Invalidate(); zg1.Invalidate();
} }
private void SaveSettings_Click(object sender, EventArgs e) private void SaveSettings_Click(object sender, EventArgs e)

View File

@ -172,6 +172,13 @@ namespace ArdupilotMega.GCSViews
comPort.Open(); comPort.Open();
comPort.WriteLine("");
comPort.WriteLine("");
comPort.WriteLine("");
comPort.WriteLine("");
comPort.WriteLine("");
comPort.WriteLine("");
System.Threading.Thread t11 = new System.Threading.Thread(delegate() System.Threading.Thread t11 = new System.Threading.Thread(delegate()
{ {
threadrun = true; threadrun = true;

View File

@ -504,11 +504,19 @@ namespace ArdupilotMega
int min, max, trim = 0; int min, max, trim = 0;
if (MainV2.comPort.param.Count > 0) if (MainV2.comPort.param.Count > 0)
{
try
{ {
min = (int)(float)(MainV2.comPort.param["RC" + chan + "_MIN"]); min = (int)(float)(MainV2.comPort.param["RC" + chan + "_MIN"]);
max = (int)(float)(MainV2.comPort.param["RC" + chan + "_MAX"]); max = (int)(float)(MainV2.comPort.param["RC" + chan + "_MAX"]);
trim = (int)(float)(MainV2.comPort.param["RC" + chan + "_TRIM"]); trim = (int)(float)(MainV2.comPort.param["RC" + chan + "_TRIM"]);
} }
catch {
min = 1000;
max = 2000;
trim = 1500;
}
}
else else
{ {
min = 1000; min = 1000;

View File

@ -1275,6 +1275,7 @@ namespace ArdupilotMega
if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_REQUEST && buffer[9] == 0) if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_REQUEST && buffer[9] == 0)
{ {
param["WP_TOTAL"] = (float)wp_total - 1; param["WP_TOTAL"] = (float)wp_total - 1;
param["CMD_TOTAL"] = (float)wp_total - 1;
MainV2.givecomport = false; MainV2.givecomport = false;
return; return;
} }
@ -1647,7 +1648,7 @@ namespace ArdupilotMega
if (bpstime.Second != DateTime.Now.Second && !logreadmode) if (bpstime.Second != DateTime.Now.Second && !logreadmode)
{ {
Console.WriteLine("bps {0} loss {1} left {2}", bps1, synclost, BaseStream.BytesToRead); Console.WriteLine("bps {0} loss {1} left {2} mem {3}", bps1, synclost, BaseStream.BytesToRead,System.GC.GetTotalMemory(false));
bps2 = bps1; // prev sec bps2 = bps1; // prev sec
bps1 = 0; // current sec bps1 = 0; // current sec
bpstime = DateTime.Now; bpstime = DateTime.Now;

View File

@ -468,6 +468,7 @@ namespace ArdupilotMega
private void MenuConfiguration_Click(object sender, EventArgs e) private void MenuConfiguration_Click(object sender, EventArgs e)
{ {
MyView.SuspendLayout();
MyView.Controls.Clear(); MyView.Controls.Clear();
GCSViews.Terminal.threadrun = false; GCSViews.Terminal.threadrun = false;
@ -486,13 +487,11 @@ namespace ArdupilotMega
UserControl temp = Configuration; UserControl temp = Configuration;
temp.SuspendLayout();
fixtheme(temp); fixtheme(temp);
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top; //temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
temp.Location = new Point(0, MainMenu.Height); temp.Location = new Point(0, 0);
temp.Dock = DockStyle.Fill; temp.Dock = DockStyle.Fill;
@ -500,9 +499,11 @@ namespace ArdupilotMega
temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28); temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
temp.ResumeLayout();
MyView.Controls.Add(temp); MyView.Controls.Add(temp);
temp.ResumeLayout(); MyView.ResumeLayout();
} }
private void MenuSimulation_Click(object sender, EventArgs e) private void MenuSimulation_Click(object sender, EventArgs e)
@ -562,7 +563,19 @@ namespace ArdupilotMega
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.disconnect; this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.disconnect;
UserControl temp = new GCSViews.Terminal(); // dispose of old else memory leak
if (Terminal != null)
{
try
{
Terminal.Dispose();
}
catch { }
}
Terminal = new GCSViews.Terminal();
UserControl temp = Terminal;
fixtheme(temp); fixtheme(temp);

View File

@ -332,7 +332,7 @@ namespace ArdupilotMega
cs.datetime = mine.lastlogread; cs.datetime = mine.lastlogread;
cs.UpdateCurrentSettings(null, true); cs.UpdateCurrentSettings(null, true, mine);
try try
{ {
@ -360,6 +360,7 @@ namespace ArdupilotMega
writeKML(logfile + ".kml"); writeKML(logfile + ".kml");
progressBar1.Value = 100;
} }
} }

View File

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

View File

@ -135,7 +135,7 @@ namespace ArdupilotMega.Setup
System.Threading.Thread.Sleep(5); System.Threading.Thread.Sleep(5);
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true); MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
if (MainV2.cs.ch1in > 800 && MainV2.cs.ch1in < 2200) if (MainV2.cs.ch1in > 800 && MainV2.cs.ch1in < 2200)
{ {
@ -192,7 +192,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 click ok to continue");
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true); MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
rctrim[0] = MainV2.cs.ch1in; rctrim[0] = MainV2.cs.ch1in;
rctrim[1] = MainV2.cs.ch2in; rctrim[1] = MainV2.cs.ch2in;

View File

@ -11,7 +11,7 @@
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" /> <dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
</dsig:Transforms> </dsig:Transforms>
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" /> <dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
<dsig:DigestValue>FgyYFBDKA+EmX+ZazsEdbI/ME7o=</dsig:DigestValue> <dsig:DigestValue>S+dMQOC9TeJyQiYvhw37LpJxZU0=</dsig:DigestValue>
</hash> </hash>
</dependentAssembly> </dependentAssembly>
</dependency> </dependency>

View File

@ -2,10 +2,12 @@
function format { function format {
DIR=$1 DIR=$1
find $DIR -regex ".*\.\(h\|cpp\|pde\)" -exec astyle {} \; find $DIR -regex ".*\.\(h\|cpp\|pde\)" -exec astyle {} \;
find $DIR -regex ".*\.\(h\|cpp\|pde\)" -exec rm {}.orig \; find $DIR -regex ".*\.\(h\|cpp\|pde\)" -exec rm -f {}.orig \;
} }
format apo format apo
format ArduRover format ArduRover
format ArduBoat format ArduBoat
format libraries/APO format libraries/APO
format libraries/AP_Common
format libraries/AP_GPS

View File

@ -302,14 +302,18 @@ public:
/// ///
/// @return The parent group, or NULL if the variable is not grouped. /// @return The parent group, or NULL if the variable is not grouped.
/// ///
AP_Var_group *group(void) { return _group; } AP_Var_group *group(void) {
return _group;
}
/// Returns the first variable in the global list. /// Returns the first variable in the global list.
/// ///
/// @return The first variable in the global list, or NULL if /// @return The first variable in the global list, or NULL if
/// there are none. /// there are none.
/// ///
static AP_Var *first(void) { return _variables; } static AP_Var *first(void) {
return _variables;
}
/// Returns the next variable in the global list. /// Returns the next variable in the global list.
/// ///
@ -367,7 +371,9 @@ public:
/// ///
/// @return The sum of sizeof(*this) for all constructed AP_Var subclass instances. /// @return The sum of sizeof(*this) for all constructed AP_Var subclass instances.
/// ///
static uint16_t get_memory_use() { return _bytes_in_use; } static uint16_t get_memory_use() {
return _bytes_in_use;
}
protected: protected:
// Memory statistics // Memory statistics

View File

@ -42,12 +42,12 @@ AP_DCM_HIL::setHil(float _roll, float _pitch, float _yaw,
float sPitch = sin(pitch), cPitch = cos(pitch); float sPitch = sin(pitch), cPitch = cos(pitch);
float sYaw = sin(yaw), cYaw = cos(yaw); float sYaw = sin(yaw), cYaw = cos(yaw);
_dcm_matrix.a.x = cPitch*cYaw; _dcm_matrix.a.x = cPitch*cYaw;
_dcm_matrix.a.y = cPitch*sYaw; _dcm_matrix.a.y = -cRoll*sYaw+sRoll*sPitch*cYaw;
_dcm_matrix.a.z = -sPitch; _dcm_matrix.a.z = sRoll*sYaw+cRoll*sPitch*cYaw;
_dcm_matrix.b.x = -cRoll*sYaw+sRoll*sPitch*cYaw; _dcm_matrix.b.x = cPitch*sYaw;
_dcm_matrix.b.y = cRoll*cYaw+sRoll*sPitch*sYaw; _dcm_matrix.b.y = cRoll*cYaw+sRoll*sPitch*sYaw;
_dcm_matrix.b.z = sRoll*cPitch; _dcm_matrix.b.z = -sRoll*cYaw+cRoll*sPitch*sYaw;
_dcm_matrix.c.x = sRoll*sYaw+cRoll*sPitch*cYaw; _dcm_matrix.c.x = -sPitch;
_dcm_matrix.c.y = -sRoll*cYaw+cRoll*sPitch*sYaw; _dcm_matrix.c.y = sRoll*cPitch;
_dcm_matrix.c.z = cRoll*cPitch; _dcm_matrix.c.z = cRoll*cPitch;
} }

View File

@ -41,8 +41,8 @@ AP_GPS_406::_configure_gps(void)
const uint8_t gps_checksum[] = {0xA8, 0xAA, 0xAD, 0xAF, 0xC1}; const uint8_t gps_checksum[] = {0xA8, 0xAA, 0xAD, 0xAF, 0xC1};
const uint8_t gps_ender[] = {0xB0, 0xB3}; const uint8_t gps_ender[] = {0xB0, 0xB3};
for(int z = 0; z < 2; z++){ for(int z = 0; z < 2; z++) {
for(int x = 0; x < 5; x++){ for(int x = 0; x < 5; x++) {
_port->write(gps_header, sizeof(gps_header)); // Prints the msg header, is the same header for all msg.. _port->write(gps_header, sizeof(gps_header)); // Prints the msg header, is the same header for all msg..
_port->write(gps_payload[x]); // Prints the payload, is not the same for every msg _port->write(gps_payload[x]); // Prints the payload, is not the same for every msg
for(int y = 0; y < 6; y++) // Prints 6 zeros for(int y = 0; y < 6; y++) // Prints 6 zeros

View File

@ -56,12 +56,12 @@ AP_GPS_IMU::read(void)
numc = _port->available(); numc = _port->available();
if (numc > 0){ if (numc > 0) {
for (int i=0;i<numc;i++){ // Process bytes received for (int i=0; i<numc; i++) { // Process bytes received
data = _port->read(); data = _port->read();
switch(step){ //Normally we start from zero. This is a state machine switch(step) { //Normally we start from zero. This is a state machine
case 0: case 0:
if(data == 0x44) // IMU sync char 1 if(data == 0x44) // IMU sync char 1
step++; //OH first data packet is correct, so jump to the next step step++; //OH first data packet is correct, so jump to the next step
@ -92,7 +92,7 @@ AP_GPS_IMU::read(void)
payload_length = data; payload_length = data;
checksum(payload_length); checksum(payload_length);
step++; step++;
if (payload_length > 28){ if (payload_length > 28) {
step = 0; //Bad data, so restart to step zero and try again. step = 0; //Bad data, so restart to step zero and try again.
payload_counter = 0; payload_counter = 0;
ck_a = 0; ck_a = 0;

View File

@ -7,7 +7,7 @@
#define MAXPAYLOAD 32 #define MAXPAYLOAD 32
class AP_GPS_IMU : public GPS { class AP_GPS_IMU : public GPS {
public: public:
// Methods // Methods
AP_GPS_IMU(Stream *s); AP_GPS_IMU(Stream *s);
@ -25,7 +25,7 @@ class AP_GPS_IMU : public GPS {
virtual void setHIL(long time, float latitude, float longitude, float altitude, virtual void setHIL(long time, float latitude, float longitude, float altitude,
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats); float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
private: private:
// Packet checksums // Packet checksums
uint8_t ck_a; uint8_t ck_a;
uint8_t ck_b; uint8_t ck_b;

View File

@ -56,13 +56,13 @@ AP_GPS_MTK::read(void)
bool parsed = false; bool parsed = false;
numc = _port->available(); numc = _port->available();
for (int i = 0; i < numc; i++){ // Process bytes received for (int i = 0; i < numc; i++) { // Process bytes received
// read the next byte // read the next byte
data = _port->read(); data = _port->read();
restart: restart:
switch(_step){ switch(_step) {
// Message preamble, class, ID detection // Message preamble, class, ID detection
// //

View File

@ -64,7 +64,7 @@ AP_GPS_MTK16::read(void)
data = _port->read(); data = _port->read();
restart: restart:
switch(_step){ switch(_step) {
// Message preamble, class, ID detection // Message preamble, class, ID detection
// //

View File

@ -10,6 +10,8 @@ class AP_GPS_None : public GPS
public: public:
AP_GPS_None(Stream *s) : GPS(s) {} AP_GPS_None(Stream *s) : GPS(s) {}
virtual void init(void) {}; virtual void init(void) {};
virtual bool read(void) { return false; }; virtual bool read(void) {
return false;
};
}; };
#endif #endif

View File

@ -65,7 +65,7 @@ AP_GPS_SIRF::read(void)
// read the next byte // read the next byte
data = _port->read(); data = _port->read();
switch(_step){ switch(_step) {
// Message preamble detection // Message preamble detection
// //

View File

@ -49,12 +49,12 @@ AP_GPS_UBLOX::read(void)
bool parsed = false; bool parsed = false;
numc = _port->available(); numc = _port->available();
for (int i = 0; i < numc; i++){ // Process bytes received for (int i = 0; i < numc; i++) { // Process bytes received
// read the next byte // read the next byte
data = _port->read(); data = _port->read();
switch(_step){ switch(_step) {
// Message preamble detection // Message preamble detection
// //

View File

@ -43,7 +43,9 @@ public:
/// ///
/// @returns Current GPS status /// @returns Current GPS status
/// ///
GPS_Status status(void) { return _status; } GPS_Status status(void) {
return _status;
}
/// GPS time epoch codes /// GPS time epoch codes
/// ///
@ -59,7 +61,9 @@ public:
/// ///
/// @returns Current GPS time epoch code /// @returns Current GPS time epoch code
/// ///
GPS_Time_Epoch epoch(void) { return _epoch; } GPS_Time_Epoch epoch(void) {
return _epoch;
}
/// Startup initialisation. /// Startup initialisation.
/// ///

View File

@ -34,7 +34,7 @@ void loop()
{ {
delay(20); delay(20);
gps.update(); gps.update();
if (gps.new_data){ if (gps.new_data) {
Serial.print("gps:"); Serial.print("gps:");
Serial.print(" Lat:"); Serial.print(" Lat:");
Serial.print((float)gps.latitude / T7, DEC); Serial.print((float)gps.latitude / T7, DEC);

View File

@ -29,7 +29,7 @@ void setup()
void loop() void loop()
{ {
gps->update(); gps->update();
if (gps->new_data){ if (gps->new_data) {
if (gps->fix) { if (gps->fix) {
Serial.printf("\nLat: %.7f Lon: %.7f Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu", Serial.printf("\nLat: %.7f Lon: %.7f Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu",
(float)gps->latitude / T7, (float)gps->latitude / T7,

View File

@ -32,7 +32,7 @@ void loop()
{ {
delay(20); delay(20);
gps.update(); gps.update();
if (gps.new_data){ if (gps.new_data) {
Serial.print("gps:"); Serial.print("gps:");
Serial.print(" Lat:"); Serial.print(" Lat:");
Serial.print((float)gps.latitude / T7, DEC); Serial.print((float)gps.latitude / T7, DEC);

View File

@ -32,7 +32,8 @@ const uint8_t sirf_to_nmea[] = { 0xa0, 0xa2, // preamble
0x00, 0x00, // pad 0x00, 0x00, // pad
0x96, 0x00, // 38400 0x96, 0x00, // 38400
0x01, 0x25, // checksum TBD 0x01, 0x25, // checksum TBD
0xb0, 0xb3 }; // postamble 0xb0, 0xb3
}; // postamble
void setup() void setup()
{ {
@ -52,7 +53,7 @@ void setup()
void loop() void loop()
{ {
gps->update(); gps->update();
if (gps->new_data){ if (gps->new_data) {
if (gps->fix) { if (gps->fix) {
Serial.printf("\nLat: %.7f Lon: %.7f Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu", Serial.printf("\nLat: %.7f Lon: %.7f Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu",
(float)gps->latitude / T7, (float)gps->latitude / T7,

View File

@ -32,7 +32,7 @@ void loop()
{ {
delay(20); delay(20);
gps.update(); gps.update();
if (gps.new_data){ if (gps.new_data) {
Serial.print("gps:"); Serial.print("gps:");
Serial.print(" Lat:"); Serial.print(" Lat:");
Serial.print((float)gps.latitude / T7, DEC); Serial.print((float)gps.latitude / T7, DEC);