APM Planner 1.1.44

mod antenna tracker code
add extra ch 6 options
cleanup message dialogs better
fix auto fill ch6 and ch7 mode options
add progress to upload and dl wp's
fix disconnect bug on mono
This commit is contained in:
Michael Oborne 2012-02-29 21:19:54 +08:00
parent 7c09e4a5e6
commit a5e3f8d324
14 changed files with 446 additions and 342 deletions

View File

@ -65,7 +65,7 @@ namespace ArdupilotMega.Antenna
ComPort.Write(buffer, 0, buffer.Length);
// accel
target = 3;
target = 5;
buffer = new byte[] { 0x89, PanAddress, (byte)(target & 0x7F), (byte)((target >> 7) & 0x7F) };
ComPort.Write(buffer, 0, buffer.Length);
@ -84,19 +84,31 @@ namespace ArdupilotMega.Antenna
return input;
}
double wrap_range(double input,double range)
{
if (input > range)
return input - 360;
if (input < -range)
return input + 360;
return input;
}
public bool Pan(double Angle)
{
// using a byte so it will autowrap
double range = Math.Abs(PanStartRange - PanEndRange);
double centerrange = (range / 2) - TrimPan;
// get relative center based on tracking center
double rangeleft = PanStartRange - TrimPan;
double rangeright = PanEndRange - TrimPan;
double centerpos = 127;
// get the output angle the tracker needs to point and constrain the output to the allowed options
short PointAtAngle = Constrain(wrap_180(Angle - TrimPan), PanStartRange, PanEndRange);
byte target = (byte)((((PointAtAngle / range) * 2.0) * 127 + 127) * _panreverse);
// conver the angle into a 0-255 value
byte target = (byte)((((PointAtAngle / range) * 2.0) * 127 + centerpos) * _panreverse);
Console.WriteLine("P " + Angle + " " + target + " " + PointAtAngle);
//Console.WriteLine("P " + Angle + " " + target + " " + PointAtAngle);
var buffer = new byte[] { 0xff,PanAddress,target};
ComPort.Write(buffer, 0, buffer.Length);
@ -108,7 +120,7 @@ namespace ArdupilotMega.Antenna
{
double range = Math.Abs(TiltStartRange - TiltEndRange);
short PointAtAngle = Constrain((Angle - TrimTilt), TiltStartRange - TrimTilt, TiltEndRange - TrimTilt);
short PointAtAngle = Constrain((Angle - TrimTilt), TiltStartRange, TiltEndRange);
byte target = (byte)((((PointAtAngle / range ) * 2) * 127 + 127) * _tiltreverse);

View File

@ -35,17 +35,15 @@
this.CMB_serialport = new System.Windows.Forms.ComboBox();
this.BUT_connect = new ArdupilotMega.MyButton();
this.TRK_pantrim = new System.Windows.Forms.TrackBar();
this.TXT_panstart = new System.Windows.Forms.TextBox();
this.TXT_panstop = new System.Windows.Forms.TextBox();
this.label2 = new System.Windows.Forms.Label();
this.TXT_panrange = new System.Windows.Forms.TextBox();
this.label3 = new System.Windows.Forms.Label();
this.label4 = new System.Windows.Forms.Label();
this.label5 = new System.Windows.Forms.Label();
this.label6 = new System.Windows.Forms.Label();
this.label7 = new System.Windows.Forms.Label();
this.TXT_tiltstop = new System.Windows.Forms.TextBox();
this.TXT_tiltstart = new System.Windows.Forms.TextBox();
this.TXT_tiltrange = new System.Windows.Forms.TextBox();
this.TRK_tilttrim = new System.Windows.Forms.TrackBar();
this.label2 = new System.Windows.Forms.Label();
this.label7 = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).BeginInit();
this.SuspendLayout();
@ -109,7 +107,7 @@
//
// TRK_pantrim
//
this.TRK_pantrim.Location = new System.Drawing.Point(83, 65);
this.TRK_pantrim.Location = new System.Drawing.Point(153, 65);
this.TRK_pantrim.Maximum = 180;
this.TRK_pantrim.Minimum = -180;
this.TRK_pantrim.Name = "TRK_pantrim";
@ -117,35 +115,18 @@
this.TRK_pantrim.TabIndex = 6;
this.TRK_pantrim.Scroll += new System.EventHandler(this.TRK_pantrim_Scroll);
//
// TXT_panstart
// TXT_panrange
//
this.TXT_panstart.Location = new System.Drawing.Point(13, 65);
this.TXT_panstart.Name = "TXT_panstart";
this.TXT_panstart.Size = new System.Drawing.Size(64, 20);
this.TXT_panstart.TabIndex = 7;
this.TXT_panstart.Text = "-90";
//
// TXT_panstop
//
this.TXT_panstop.Location = new System.Drawing.Point(464, 65);
this.TXT_panstop.Name = "TXT_panstop";
this.TXT_panstop.Size = new System.Drawing.Size(64, 20);
this.TXT_panstop.TabIndex = 8;
this.TXT_panstop.Text = "90";
//
// label2
//
this.label2.AutoSize = true;
this.label2.Location = new System.Drawing.Point(461, 49);
this.label2.Name = "label2";
this.label2.Size = new System.Drawing.Size(32, 13);
this.label2.TabIndex = 9;
this.label2.Text = "Right";
this.TXT_panrange.Location = new System.Drawing.Point(83, 65);
this.TXT_panrange.Name = "TXT_panrange";
this.TXT_panrange.Size = new System.Drawing.Size(64, 20);
this.TXT_panrange.TabIndex = 7;
this.TXT_panrange.Text = "180";
//
// label3
//
this.label3.AutoSize = true;
this.label3.Location = new System.Drawing.Point(261, 49);
this.label3.Location = new System.Drawing.Point(331, 49);
this.label3.Name = "label3";
this.label3.Size = new System.Drawing.Size(38, 13);
this.label3.TabIndex = 10;
@ -154,58 +135,41 @@
// label4
//
this.label4.AutoSize = true;
this.label4.Location = new System.Drawing.Point(13, 49);
this.label4.Location = new System.Drawing.Point(83, 49);
this.label4.Name = "label4";
this.label4.Size = new System.Drawing.Size(25, 13);
this.label4.Size = new System.Drawing.Size(56, 13);
this.label4.TabIndex = 11;
this.label4.Text = "Left";
this.label4.Text = "Range -/+";
//
// label5
//
this.label5.AutoSize = true;
this.label5.Location = new System.Drawing.Point(13, 125);
this.label5.Location = new System.Drawing.Point(83, 125);
this.label5.Name = "label5";
this.label5.Size = new System.Drawing.Size(35, 13);
this.label5.Size = new System.Drawing.Size(56, 13);
this.label5.TabIndex = 17;
this.label5.Text = "Down";
this.label5.Text = "Range -/+";
//
// label6
//
this.label6.AutoSize = true;
this.label6.Location = new System.Drawing.Point(261, 125);
this.label6.Location = new System.Drawing.Point(331, 125);
this.label6.Name = "label6";
this.label6.Size = new System.Drawing.Size(38, 13);
this.label6.TabIndex = 16;
this.label6.Text = "Center";
//
// label7
// TXT_tiltrange
//
this.label7.AutoSize = true;
this.label7.Location = new System.Drawing.Point(461, 125);
this.label7.Name = "label7";
this.label7.Size = new System.Drawing.Size(21, 13);
this.label7.TabIndex = 15;
this.label7.Text = "Up";
//
// TXT_tiltstop
//
this.TXT_tiltstop.Location = new System.Drawing.Point(464, 141);
this.TXT_tiltstop.Name = "TXT_tiltstop";
this.TXT_tiltstop.Size = new System.Drawing.Size(64, 20);
this.TXT_tiltstop.TabIndex = 14;
this.TXT_tiltstop.Text = "90";
//
// TXT_tiltstart
//
this.TXT_tiltstart.Location = new System.Drawing.Point(13, 141);
this.TXT_tiltstart.Name = "TXT_tiltstart";
this.TXT_tiltstart.Size = new System.Drawing.Size(64, 20);
this.TXT_tiltstart.TabIndex = 13;
this.TXT_tiltstart.Text = "0";
this.TXT_tiltrange.Location = new System.Drawing.Point(83, 141);
this.TXT_tiltrange.Name = "TXT_tiltrange";
this.TXT_tiltrange.Size = new System.Drawing.Size(64, 20);
this.TXT_tiltrange.TabIndex = 13;
this.TXT_tiltrange.Text = "90";
//
// TRK_tilttrim
//
this.TRK_tilttrim.Location = new System.Drawing.Point(83, 141);
this.TRK_tilttrim.Location = new System.Drawing.Point(153, 141);
this.TRK_tilttrim.Maximum = 90;
this.TRK_tilttrim.Minimum = -90;
this.TRK_tilttrim.Name = "TRK_tilttrim";
@ -214,22 +178,38 @@
this.TRK_tilttrim.Value = 45;
this.TRK_tilttrim.Scroll += new System.EventHandler(this.TRK_tilttrim_Scroll);
//
// label2
//
this.label2.AutoSize = true;
this.label2.Location = new System.Drawing.Point(13, 68);
this.label2.Name = "label2";
this.label2.Size = new System.Drawing.Size(26, 13);
this.label2.TabIndex = 18;
this.label2.Text = "Pan";
//
// label7
//
this.label7.AutoSize = true;
this.label7.Location = new System.Drawing.Point(13, 144);
this.label7.Name = "label7";
this.label7.Size = new System.Drawing.Size(21, 13);
this.label7.TabIndex = 19;
this.label7.Text = "Tilt";
//
// Tracker
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.ClientSize = new System.Drawing.Size(569, 195);
this.Controls.Add(this.label7);
this.Controls.Add(this.label2);
this.Controls.Add(this.label5);
this.Controls.Add(this.label6);
this.Controls.Add(this.label7);
this.Controls.Add(this.TXT_tiltstop);
this.Controls.Add(this.TXT_tiltstart);
this.Controls.Add(this.TXT_tiltrange);
this.Controls.Add(this.TRK_tilttrim);
this.Controls.Add(this.label4);
this.Controls.Add(this.label3);
this.Controls.Add(this.label2);
this.Controls.Add(this.TXT_panstop);
this.Controls.Add(this.TXT_panstart);
this.Controls.Add(this.TXT_panrange);
this.Controls.Add(this.TRK_pantrim);
this.Controls.Add(this.CMB_baudrate);
this.Controls.Add(this.BUT_connect);
@ -254,16 +234,14 @@
private MyButton BUT_connect;
private System.Windows.Forms.ComboBox CMB_serialport;
private System.Windows.Forms.TrackBar TRK_pantrim;
private System.Windows.Forms.TextBox TXT_panstart;
private System.Windows.Forms.TextBox TXT_panstop;
private System.Windows.Forms.Label label2;
private System.Windows.Forms.TextBox TXT_panrange;
private System.Windows.Forms.Label label3;
private System.Windows.Forms.Label label4;
private System.Windows.Forms.Label label5;
private System.Windows.Forms.Label label6;
private System.Windows.Forms.Label label7;
private System.Windows.Forms.TextBox TXT_tiltstop;
private System.Windows.Forms.TextBox TXT_tiltstart;
private System.Windows.Forms.TextBox TXT_tiltrange;
private System.Windows.Forms.TrackBar TRK_tilttrim;
private System.Windows.Forms.Label label2;
private System.Windows.Forms.Label label7;
}
}

View File

@ -39,6 +39,11 @@ namespace ArdupilotMega.Antenna
return;
}
if (tracker != null && tracker.ComPort != null && tracker.ComPort.IsOpen)
{
tracker.ComPort.Close();
}
tracker = new ArdupilotMega.Antenna.Maestro();
try
@ -53,12 +58,12 @@ namespace ArdupilotMega.Antenna
try
{
tracker.PanStartRange = int.Parse(TXT_panstart.Text);
tracker.PanEndRange = int.Parse(TXT_panstop.Text);
tracker.PanStartRange = int.Parse(TXT_panrange.Text) / 2 * -1;
tracker.PanEndRange = int.Parse(TXT_panrange.Text) / 2;
tracker.TrimPan = TRK_pantrim.Value;
tracker.TiltStartRange = int.Parse(TXT_tiltstart.Text);
tracker.TiltEndRange = int.Parse(TXT_tiltstop.Text);
tracker.TiltStartRange = int.Parse(TXT_tiltrange.Text) / 2 * -1;
tracker.TiltEndRange = int.Parse(TXT_tiltrange.Text) / 2;
tracker.TrimTilt = TRK_tilttrim.Value;
}
@ -75,21 +80,7 @@ namespace ArdupilotMega.Antenna
IsBackground = true,
Name = "Antenna Tracker"
};
t12.Start();
/*
for (int a = ting.PanStartRange; a < ting.PanEndRange; a++)
{
System.Threading.Thread.Sleep(100);
ting.Pan(a);
}
for (int a = ting.TiltStartRange; a < ting.TiltEndRange; a++)
{
System.Threading.Thread.Sleep(100);
ting.Tilt(a);
}
*/
t12.Start();
}
}
}

View File

@ -442,6 +442,7 @@
<Compile Include="Setup\Setup.Designer.cs">
<DependentUpon>Setup.cs</DependentUpon>
</Compile>
<Compile Include="Speech.cs" />
<Compile Include="Splash.cs">
<SubType>Form</SubType>
</Compile>

View File

@ -379,7 +379,9 @@ namespace ArdupilotMega
CH6_OPTFLOW_KI = 18,
CH6_OPTFLOW_KD = 19,
CH6_NAV_I = 20
CH6_NAV_I = 20,
CH6_LOITER_RATE_P = 22
}
@ -706,7 +708,11 @@ namespace ArdupilotMega
MainV2.fixtheme(form);
return form.ShowDialog();
DialogResult dialogResult =form.ShowDialog();
form.Dispose();
return dialogResult;
}
static void chk_CheckStateChanged(object sender, EventArgs e)
@ -756,11 +762,17 @@ namespace ArdupilotMega
MainV2.fixtheme(form);
DialogResult dialogResult = form.ShowDialog();
DialogResult dialogResult = DialogResult.Cancel;
dialogResult = form.ShowDialog();
if (dialogResult == DialogResult.OK)
{
value = textBox.Text;
}
form.Dispose();
return dialogResult;
}

View File

@ -197,7 +197,7 @@ namespace ArdupilotMega
public float DistToMAV
{
get
{
{
// shrinking factor for longitude going to poles direction
double rads = Math.Abs(HomeLocation.Lat) * 0.0174532925;
double scaleLongDown = Math.Cos(rads);
@ -227,7 +227,7 @@ namespace ArdupilotMega
public float AZToMAV
{
get
{
{
// shrinking factor for longitude going to poles direction
double rads = Math.Abs(HomeLocation.Lat) * 0.0174532925;
double scaleLongDown = Math.Cos(rads);
@ -317,11 +317,11 @@ namespace ArdupilotMega
try
{
while (messages.Count > 5)
{
messages.RemoveAt(0);
}
messages.Add(logdata + "\n");
while (messages.Count > 5)
{
messages.RemoveAt(0);
}
messages.Add(logdata + "\n");
}
catch { }
@ -581,7 +581,7 @@ namespace ArdupilotMega
packetdropremote = sysstatus.packet_drop;
if (oldmode != mode && MainV2.speechenable && MainV2.getConfig("speechmodeenabled") == "True")
if (oldmode != mode && MainV2.speechenable && MainV2.talk != null && MainV2.getConfig("speechmodeenabled") == "True")
{
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechmode")));
}
@ -732,7 +732,7 @@ namespace ArdupilotMega
wpno = wpcur.seq;
if (oldwp != wpno && MainV2.speechenable && MainV2.getConfig("speechwaypointenabled") == "True")
if (oldwp != wpno && MainV2.speechenable && MainV2.talk != null && MainV2.getConfig("speechwaypointenabled") == "True")
{
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint")));
}
@ -901,4 +901,4 @@ namespace ArdupilotMega
//low pass the outputs for better results!
}
}
}
}

View File

@ -95,6 +95,10 @@ namespace ArdupilotMega.GCSViews
if (tooltips.Count == 0)
readToolTips();
// ensure the fields are populated before setting them
CH7_OPT.DataSource = Enum.GetNames(typeof(Common.ac2ch7modes));
TUNE.DataSource = Enum.GetNames(typeof(Common.ac2ch6modes));
// prefill all fields
param = MainV2.comPort.param;
processToScreen();
@ -165,9 +169,6 @@ namespace ArdupilotMega.GCSViews
CMB_distunits.DataSource = Enum.GetNames(typeof(Common.distances));
CMB_speedunits.DataSource = Enum.GetNames(typeof(Common.speeds));
CH7_OPT.DataSource = Enum.GetNames(typeof(Common.ac2ch7modes));
TUNE.DataSource = Enum.GetNames(typeof(Common.ac2ch6modes));
if (MainV2.config["distunits"] != null)
CMB_distunits.Text = MainV2.config["distunits"].ToString();
if (MainV2.config["speedunits"] != null)
@ -184,13 +185,13 @@ namespace ArdupilotMega.GCSViews
CMB_language.DisplayMember = "DisplayName";
CMB_language.DataSource = languages;
ci = Thread.CurrentThread.CurrentUICulture;
ci = Thread.CurrentThread.CurrentUICulture;
for (int i = 0; i < languages.Count; i++)
{
{
if (ci.IsChildOf(languages[i]))
{
CMB_language.SelectedIndex = i;
break;
{
CMB_language.SelectedIndex = i;
break;
}
}
CMB_language.SelectedIndexChanged += CMB_language_SelectedIndexChanged;
@ -555,23 +556,23 @@ namespace ArdupilotMega.GCSViews
if (text.Length > 0)
{
if (text[0].GetType() == typeof(NumericUpDown))
{
decimal option = (decimal)(float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString()));
((NumericUpDown)text[0]).Value = option;
((NumericUpDown)text[0]).BackColor = Color.Green;
}
{
decimal option = (decimal)(float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString()));
((NumericUpDown)text[0]).Value = option;
((NumericUpDown)text[0]).BackColor = Color.Green;
}
else if (text[0].GetType() == typeof(ComboBox))
{
int option = (int)(float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString()));
((ComboBox)text[0]).SelectedIndex = option;
((ComboBox)text[0]).BackColor = Color.Green;
}
{
int option = (int)(float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString()));
((ComboBox)text[0]).SelectedIndex = option;
((ComboBox)text[0]).BackColor = Color.Green;
}
}
}
catch { ((Control)text[0]).BackColor = Color.Red; }
Params.Focus();
}
}
private void BUT_load_Click(object sender, EventArgs e)
{
@ -599,12 +600,12 @@ namespace ArdupilotMega.GCSViews
continue;
if (index2 != -1)
line = line.Replace(',','.');
line = line.Replace(',', '.');
string name = line.Substring(0, index);
float value = float.Parse(line.Substring(index + 1), new System.Globalization.CultureInfo("en-US"));
MAVLink.modifyParamForDisplay(true,name,ref value);
MAVLink.modifyParamForDisplay(true, name, ref value);
// set param table as well
foreach (DataGridViewRow row in Params.Rows)
@ -815,9 +816,10 @@ namespace ArdupilotMega.GCSViews
{
DsError.ThrowExceptionForHR(hr);
}
catch (Exception ex) {
MessageBox.Show("Can not add video source\n" + ex.ToString());
return;
catch (Exception ex)
{
MessageBox.Show("Can not add video source\n" + ex.ToString());
return;
}
// Find the stream config interface
@ -947,7 +949,7 @@ namespace ArdupilotMega.GCSViews
}
catch { MessageBox.Show("Error: getting param list"); }

View File

@ -1195,69 +1195,82 @@ namespace ArdupilotMega.GCSViews
/// <param name="sender"></param>
/// <param name="e"></param>
internal void BUT_read_Click(object sender, EventArgs e)
{
Controls.ProgressReporterDialogue frmProgressReporter = new Controls.ProgressReporterDialogue
{
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
Text = "Receiving WP's"
};
frmProgressReporter.DoWork += getWPs;
frmProgressReporter.UpdateProgressAndStatus(-1, "Receiving WP's");
MainV2.fixtheme(frmProgressReporter);
frmProgressReporter.RunBackgroundOperationAsync();
}
void getWPs(object sender, Controls.ProgressWorkerEventArgs e)
{
List<Locationwp> cmds = new List<Locationwp>();
int error = 0;
System.Threading.Thread t12 = new System.Threading.Thread(delegate()
try
{
try
MAVLink port = MainV2.comPort;
if (!port.BaseStream.IsOpen)
{
MAVLink port = MainV2.comPort;
if (!port.BaseStream.IsOpen)
{
throw new Exception("Please Connect First!");
}
MainV2.givecomport = true;
param = port.param;
log.Info("Getting WP #");
int cmdcount = port.getWPCount();
for (ushort a = 0; a < cmdcount; a++)
{
log.Info("Getting WP" + a);
cmds.Add(port.getWP(a));
}
port.setWPACK();
log.Info("Done");
throw new Exception("Please Connect First!");
}
catch (Exception ex) { error = 1; MessageBox.Show("Error : " + ex.ToString()); }
try
MainV2.givecomport = true;
param = port.param;
log.Info("Getting WP #");
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(0, "Getting WP count");
int cmdcount = port.getWPCount();
for (ushort a = 0; a < cmdcount; a++)
{
this.BeginInvoke((System.Threading.ThreadStart)delegate()
log.Info("Getting WP" + a);
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(a * 100 / cmdcount, "Getting WP " + a);
cmds.Add(port.getWP(a));
}
port.setWPACK();
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(100, "Done");
log.Info("Done");
}
catch (Exception ex) { error = 1; MessageBox.Show("Error : " + ex.ToString()); }
try
{
this.BeginInvoke((System.Threading.ThreadStart)delegate()
{
if (error == 0)
{
if (error == 0)
try
{
try
{
processToScreen(cmds);
}
catch (Exception exx) { log.Info(exx.ToString()); }
processToScreen(cmds);
}
catch (Exception exx) { log.Info(exx.ToString()); }
}
MainV2.givecomport = false;
MainV2.givecomport = false;
BUT_read.Enabled = true;
BUT_read.Enabled = true;
writeKML();
writeKML();
});
}
catch (Exception exx) { log.Info(exx.ToString()); }
});
t12.IsBackground = true;
t12.Name = "Read wps";
t12.Start();
MainV2.threads.Add(t12);
BUT_read.Enabled = false;
});
}
catch (Exception exx) { log.Info(exx.ToString()); }
}
/// <summary>
@ -1292,111 +1305,118 @@ namespace ArdupilotMega.GCSViews
}
}
System.Threading.Thread t12 = new System.Threading.Thread(delegate()
Controls.ProgressReporterDialogue frmProgressReporter = new Controls.ProgressReporterDialogue
{
try
{
MAVLink port = MainV2.comPort;
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
Text = "Sending WP's"
};
if (!port.BaseStream.IsOpen)
{
throw new Exception("Please Connect First!");
}
frmProgressReporter.DoWork += saveWPs;
frmProgressReporter.UpdateProgressAndStatus(-1, "Sending WP's");
MainV2.givecomport = true;
MainV2.fixtheme(frmProgressReporter);
Locationwp home = new Locationwp();
frmProgressReporter.RunBackgroundOperationAsync();
try
{
home.id = (byte)MAVLink.MAV_CMD.WAYPOINT;
home.lat = (float.Parse(TXT_homelat.Text));
home.lng = (float.Parse(TXT_homelng.Text));
home.alt = (float.Parse(TXT_homealt.Text) / MainV2.cs.multiplierdist); // use saved home
}
catch { throw new Exception("Your home location is invalid"); }
port.setWPTotal((ushort)(Commands.Rows.Count + 1)); // + home
port.setWP(home, (ushort)0, MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL, 0);
MAVLink.MAV_FRAME frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
// process grid to memory eeprom
for (int a = 0; a < Commands.Rows.Count - 0; a++)
{
Locationwp temp = new Locationwp();
temp.id = (byte)(int)Enum.Parse(typeof(MAVLink.MAV_CMD), Commands.Rows[a].Cells[Command.Index].Value.ToString(), false);
temp.p1 = float.Parse(Commands.Rows[a].Cells[Param1.Index].Value.ToString());
if (temp.id < (byte)MAVLink.MAV_CMD.LAST || temp.id == (byte)MAVLink.MAV_CMD.DO_SET_HOME)
{
if (CHK_altmode.Checked)
{
frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL;
}
else
{
frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
}
}
temp.alt = (float)(double.Parse(Commands.Rows[a].Cells[Alt.Index].Value.ToString()) / MainV2.cs.multiplierdist);
temp.lat = (float)(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()));
temp.lng = (float)(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()));
temp.p2 = (float)(double.Parse(Commands.Rows[a].Cells[Param2.Index].Value.ToString()));
temp.p3 = (float)(double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()));
temp.p4 = (float)(double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()));
port.setWP(temp, (ushort)(a + 1), frame, 0);
}
port.setWPACK();
if (CHK_holdalt.Checked)
{
port.setParam("ALT_HOLD_RTL", int.Parse(TXT_DefaultAlt.Text) / MainV2.cs.multiplierdist);
}
else
{
port.setParam("ALT_HOLD_RTL", -1);
}
port.setParam("WP_RADIUS", (byte)int.Parse(TXT_WPRad.Text) / MainV2.cs.multiplierdist);
try
{
port.setParam("WP_LOITER_RAD", (byte)(int.Parse(TXT_loiterrad.Text) / MainV2.cs.multiplierdist));
}
catch
{
port.setParam("LOITER_RAD", (byte)int.Parse(TXT_loiterrad.Text) / MainV2.cs.multiplierdist);
}
}
catch (Exception ex) { MessageBox.Show("Error : " + ex.ToString()); }
MainV2.givecomport = false;
try
{
this.BeginInvoke((System.Threading.ThreadStart)delegate()
{
BUT_write.Enabled = true;
});
}
catch { }
});
t12.IsBackground = true;
t12.Name = "Write wps";
t12.Start();
MainV2.threads.Add(t12);
MainMap.Focus();
BUT_write.Enabled = false;
}
void saveWPs(object sender, Controls.ProgressWorkerEventArgs e)
{
try
{
MAVLink port = MainV2.comPort;
if (!port.BaseStream.IsOpen)
{
throw new Exception("Please Connect First!");
}
MainV2.givecomport = true;
Locationwp home = new Locationwp();
try
{
home.id = (byte)MAVLink.MAV_CMD.WAYPOINT;
home.lat = (float.Parse(TXT_homelat.Text));
home.lng = (float.Parse(TXT_homelng.Text));
home.alt = (float.Parse(TXT_homealt.Text) / MainV2.cs.multiplierdist); // use saved home
}
catch { throw new Exception("Your home location is invalid"); }
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(0, "Set Total WPs ");
port.setWPTotal((ushort)(Commands.Rows.Count + 1)); // + home
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(0, "Set Home");
port.setWP(home, (ushort)0, MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL, 0);
MAVLink.MAV_FRAME frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
// process grid to memory eeprom
for (int a = 0; a < Commands.Rows.Count - 0; a++)
{
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(a * 100 / Commands.Rows.Count, "Setting WP " + a);
Locationwp temp = new Locationwp();
temp.id = (byte)(int)Enum.Parse(typeof(MAVLink.MAV_CMD), Commands.Rows[a].Cells[Command.Index].Value.ToString(), false);
temp.p1 = float.Parse(Commands.Rows[a].Cells[Param1.Index].Value.ToString());
if (temp.id < (byte)MAVLink.MAV_CMD.LAST || temp.id == (byte)MAVLink.MAV_CMD.DO_SET_HOME)
{
if (CHK_altmode.Checked)
{
frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL;
}
else
{
frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
}
}
temp.alt = (float)(double.Parse(Commands.Rows[a].Cells[Alt.Index].Value.ToString()) / MainV2.cs.multiplierdist);
temp.lat = (float)(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()));
temp.lng = (float)(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()));
temp.p2 = (float)(double.Parse(Commands.Rows[a].Cells[Param2.Index].Value.ToString()));
temp.p3 = (float)(double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()));
temp.p4 = (float)(double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()));
port.setWP(temp, (ushort)(a + 1), frame, 0);
}
port.setWPACK();
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(95, "Setting Params");
if (CHK_holdalt.Checked)
{
port.setParam("ALT_HOLD_RTL", int.Parse(TXT_DefaultAlt.Text) / MainV2.cs.multiplierdist);
}
else
{
port.setParam("ALT_HOLD_RTL", -1);
}
port.setParam("WP_RADIUS", (byte)int.Parse(TXT_WPRad.Text) / MainV2.cs.multiplierdist);
try
{
port.setParam("WP_LOITER_RAD", (byte)(int.Parse(TXT_loiterrad.Text) / MainV2.cs.multiplierdist));
}
catch
{
port.setParam("LOITER_RAD", (byte)int.Parse(TXT_loiterrad.Text) / MainV2.cs.multiplierdist);
}
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(100, "Done.");
}
catch (Exception ex) { MainV2.givecomport = false; throw ex; }
MainV2.givecomport = false;
}
/// <summary>

View File

@ -308,7 +308,7 @@ namespace ArdupilotMega
// Progress(-1, "Connect Failed\n" + e.Message);
if (string.IsNullOrEmpty(progressWorkerEventArgs.ErrorMessage))
progressWorkerEventArgs.ErrorMessage = "Connect Failed";
throw;
throw e;
}
//frmProgressReporter.Close();
MainV2.givecomport = false;

View File

@ -27,7 +27,7 @@ namespace ArdupilotMega
{
public partial class MainV2 : Form
{
private static readonly ILog log =
private static readonly ILog log =
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
[DllImport("user32.dll")]
public static extern int FindWindow(string szClass, string szTitle);
@ -45,7 +45,7 @@ namespace ArdupilotMega
public static bool MONO = false;
public static bool speechenable = false;
public static SpeechSynthesizer talk = new SpeechSynthesizer();
public static Speech talk = null;
public static Joystick joystick = null;
DateTime lastjoystick = DateTime.Now;
@ -105,6 +105,9 @@ namespace ArdupilotMega
var t = Type.GetType("Mono.Runtime");
MONO = (t != null);
if (!MONO)
talk = new Speech();
//talk.SpeakAsync("Welcome to APM Planner");
MyRenderer.currentpressed = MenuFlightData;
@ -261,7 +264,7 @@ namespace ArdupilotMega
if (Directory.Exists("/dev/"))
{
if (Directory.Exists("/dev/serial/by-id/"))
devs = Directory.GetFiles("/dev/serial/by-id/","*usb*");
devs = Directory.GetFiles("/dev/serial/by-id/", "*usb*");
devs = Directory.GetFiles("/dev/", "*ACM*");
devs = Directory.GetFiles("/dev/", "ttyUSB*");
}
@ -667,8 +670,12 @@ namespace ArdupilotMega
{
try
{
if (talk != null) // cancel all pending speech
talk.SpeakAsyncCancelAll();
try
{
if (talk != null) // cancel all pending speech
talk.SpeakAsyncCancelAll();
}
catch { }
if (comPort.logfile != null)
comPort.logfile.Close();
@ -676,7 +683,7 @@ namespace ArdupilotMega
comPort.BaseStream.DtrEnable = false;
comPort.Close();
}
catch { }
catch (Exception ex) { log.Debug(ex.ToString()); }
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
}
@ -789,6 +796,7 @@ namespace ArdupilotMega
}
}
catch { }
log.Debug(ex.ToString());
//MessageBox.Show("Can not establish a connection\n\n" + ex.ToString());
return;
}
@ -1281,15 +1289,15 @@ namespace ArdupilotMega
t11.Start();
if (Debugger.IsAttached)
{
{
log.Info("Skipping update test as it appears we are debugging");
}
else
{
try
{
try
{
CheckForUpdate();
}
}
catch (Exception ex)
{
log.Error("Update check failed", ex);
@ -1466,12 +1474,19 @@ namespace ArdupilotMega
pmplane.Geometry = model;
SharpKml.Dom.LookAt la = new SharpKml.Dom.LookAt()
{ Altitude = loc.Altitude.Value, Latitude = loc.Latitude.Value, Longitude = loc.Longitude.Value, Tilt = 80,
Heading = cs.yaw, AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute, Range = 50};
SharpKml.Dom.LookAt la = new SharpKml.Dom.LookAt()
{
Altitude = loc.Altitude.Value,
Latitude = loc.Latitude.Value,
Longitude = loc.Longitude.Value,
Tilt = 80,
Heading = cs.yaw,
AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute,
Range = 50
};
kml.Viewpoint = la;
kml.AddFeature(pmplane);
SharpKml.Base.Serializer serializer = new SharpKml.Base.Serializer();
@ -1645,7 +1660,7 @@ namespace ArdupilotMega
}
}
if (loadinglabel != null)
UpdateLabel(loadinglabel,"Starting Updater");
UpdateLabel(loadinglabel, "Starting Updater");
log.Info("Starting new process: " + process.StartInfo.FileName + " with " + process.StartInfo.Arguments);
process.Start();
log.Info("Quitting existing process");
@ -1677,81 +1692,81 @@ namespace ArdupilotMega
private static void CheckForUpdate()
{
var baseurl = ConfigurationManager.AppSettings["UpdateLocation"];
string path = Path.GetFileNameWithoutExtension(Application.ExecutablePath) + ".exe";
string path = Path.GetFileName(Application.ExecutablePath);
// Create a request using a URL that can receive a post.
// Create a request using a URL that can receive a post.
string requestUriString = baseurl + path;
log.Debug("Checking for update at: " + requestUriString);
var webRequest = WebRequest.Create(requestUriString);
webRequest.Timeout = 5000;
// Set the Method property of the request to POST.
// Set the Method property of the request to POST.
webRequest.Method = "HEAD";
((HttpWebRequest)webRequest).IfModifiedSince = File.GetLastWriteTimeUtc(path);
// Get the response.
// Get the response.
var response = webRequest.GetResponse();
// Display the status.
// Display the status.
log.Debug("Response status: " + ((HttpWebResponse)response).StatusDescription);
// Get the stream containing content returned by the server.
//dataStream = response.GetResponseStream();
// Open the stream using a StreamReader for easy access.
// Get the stream containing content returned by the server.
//dataStream = response.GetResponseStream();
// Open the stream using a StreamReader for easy access.
bool shouldGetFile = false;
if (File.Exists(path))
{
if (File.Exists(path))
{
var fi = new FileInfo(path);
log.Info(response.Headers[HttpResponseHeader.ETag]);
if (fi.Length != response.ContentLength) // && response.Headers[HttpResponseHeader.ETag] != "0")
{
if (fi.Length != response.ContentLength) // && response.Headers[HttpResponseHeader.ETag] != "0")
{
using (var sw = new StreamWriter(path + ".etag"))
{
sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
sw.Close();
}
shouldGetFile = true;
log.Info("Newer file found: " + path);
}
log.Info("Newer file found: " + path + " " + fi.Length + " vs " + response.ContentLength);
}
}
else
{
shouldGetFile = true;
log.Info("File does not exist: Getting " + path);
// get it
}
response.Close();
if (shouldGetFile)
{
var dr = MessageBox.Show("Update Found\n\nDo you wish to update now?", "Update Now", MessageBoxButtons.YesNo);
if (dr == DialogResult.Yes)
{
DoUpdate();
}
else
{
shouldGetFile = true;
log.Info("Newer file found: " + path);
// get it
}
response.Close();
if (shouldGetFile)
{
var dr = MessageBox.Show("Update Found\n\nDo you wish to update now?", "Update Now", MessageBoxButtons.YesNo);
if (dr == DialogResult.Yes)
{
DoUpdate();
}
else
{
return;
}
return;
}
}
}
public static void DoUpdate()
{
var loading = new Form
{
{
Width = 400,
Height = 150,
StartPosition = FormStartPosition.CenterScreen,
TopMost = true,
MinimizeBox = false,
MaximizeBox = false
};
Width = 400,
Height = 150,
StartPosition = FormStartPosition.CenterScreen,
TopMost = true,
MinimizeBox = false,
MaximizeBox = false
};
var resources = new ComponentResourceManager(typeof(MainV2));
loading.Icon = ((Icon)(resources.GetObject("$this.Icon")));
@ -1774,7 +1789,7 @@ namespace ArdupilotMega
catch (Exception ex)
{
log.Error("Error in updatecheck", ex);
}
}
//);
//t12.Name = "Update check thread";
//t12.Start();
@ -1836,7 +1851,7 @@ namespace ArdupilotMega
}
if (file.EndsWith("/"))
{
update = updatecheck(loadinglabel, baseurl + file, subdir.Replace("/", "\\") + file) && update;
update = updatecheck(loadinglabel, baseurl + file, subdir.Replace('/', Path.DirectorySeparatorChar) + file) && update;
continue;
}
if (loadinglabel != null)
@ -1919,7 +1934,7 @@ namespace ArdupilotMega
log.Info(((HttpWebResponse)response).StatusDescription);
// Get the stream containing content returned by the server.
dataStream = response.GetResponseStream();
long contlen = bytes;
byte[] buf1 = new byte[1024];

View File

@ -57,6 +57,9 @@ namespace ArdupilotMega
static void Application_ThreadException(object sender, System.Threading.ThreadExceptionEventArgs e)
{
Exception ex = e.Exception;
log.Debug(ex.ToString());
if (ex.Message == "The port is closed.") {
MessageBox.Show("Serial connection has been lost");
return;

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

View File

@ -0,0 +1,70 @@
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using System.Speech.Synthesis;
namespace ArdupilotMega
{
public class Speech
{
SpeechSynthesizer _speechwindows;
System.Diagnostics.Process _speechlinux;
bool MONO = false;
public SynthesizerState State {
get {
if (MONO)
{
return SynthesizerState.Ready;
}
else
{
return _speechwindows.State;
}
}
private set { }
}
public Speech()
{
var t = Type.GetType("Mono.Runtime");
MONO = (t != null);
if (MONO)
{
_speechlinux = new System.Diagnostics.Process();
_speechlinux.StartInfo.FileName = "festival";
}
else
{
_speechwindows = new SpeechSynthesizer();
}
}
public void SpeakAsync(string text)
{
if (MONO)
{
}
else
{
_speechwindows.SpeakAsync(text);
}
}
public void SpeakAsyncCancelAll()
{
if (MONO)
{
}
else
{
_speechwindows.SpeakAsyncCancelAll();
}
}
}
}