APM Planner 1.1.56

add ardutracker support
add load/save setting in Tracker
move getserialports to serial class
hopefully fix dtr issue for good.
This commit is contained in:
Michael Oborne 2012-03-23 20:52:12 +08:00
parent 0b94b2e470
commit c0a381f10b
14 changed files with 539 additions and 99 deletions

View File

@ -0,0 +1,155 @@
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
namespace ArdupilotMega.Antenna
{
class ArduTracker : ITrackerOutput
{
public SerialPort ComPort { get; set; }
/// <summary>
/// 0-360
/// </summary>
public double TrimPan { get; set; }
/// <summary>
/// -90 - 90
/// </summary>
public double TrimTilt { get; set; }
public int PanStartRange { get; set; }
public int TiltStartRange { get; set; }
public int PanEndRange { get; set; }
public int TiltEndRange { get; set; }
public int PanPWMRange { get; set; }
public int TiltPWMRange { get; set; }
public bool PanReverse { get { return _panreverse == 1; } set { _panreverse = value == true ? -1 : 1; } }
public bool TiltReverse { get { return _tiltreverse == 1; } set { _tiltreverse = value == true ? -1 : 1; } }
int _panreverse = 1;
int _tiltreverse = 1;
int currentpan = 1500;
int currenttilt = 1500;
public bool Init()
{
if ((PanStartRange - PanEndRange) == 0)
{
System.Windows.Forms.CustomMessageBox.Show("Invalid Pan Range", "Error");
return false;
}
if ((TiltStartRange - TiltEndRange) == 0)
{
System.Windows.Forms.CustomMessageBox.Show("Invalid Tilt Range", "Error");
return false;
}
try
{
ComPort.Open();
}
catch (Exception ex) { System.Windows.Forms.CustomMessageBox.Show("Connect failed " + ex.Message, "Error"); return false; }
return true;
}
public bool Setup()
{
return true;
}
double wrap_180(double input)
{
if (input > 180)
return input - 360;
if (input < -180)
return input + 360;
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)
{
double range = Math.Abs(PanStartRange - PanEndRange);
// get relative center based on tracking center
double rangeleft = PanStartRange - TrimPan;
double rangeright = PanEndRange - TrimPan;
double centerpos = 1500;
// 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);
// conver the angle into a 0-pwmrange value
int target = (int)((((PointAtAngle / range) * 2.0) * (PanPWMRange / 2) * _panreverse + centerpos));
// Console.WriteLine("P " + Angle + " " + target + " " + PointAtAngle);
currentpan = target;
return false;
}
public bool Tilt(double Angle)
{
double range = Math.Abs(TiltStartRange - TiltEndRange);
short PointAtAngle = Constrain((Angle - TrimTilt), TiltStartRange, TiltEndRange);
int target = (int)((((PointAtAngle / range) * 2.0) * (TiltPWMRange / 2) * _tiltreverse + 1500));
// Console.WriteLine("T " + Angle + " " + target + " " + PointAtAngle);
currenttilt = target;
return false;
}
public bool PanAndTilt(double pan, double tilt)
{
Tilt(tilt);
Pan(pan);
string command = string.Format("!!!PAN:{0:0000},TLT:{1:0000}\n", currentpan, currenttilt);
Console.Write(command);
ComPort.Write(command);
return false;
}
public bool Close()
{
try
{
ComPort.Close();
}
catch { }
return true;
}
short Constrain(double input, double min, double max)
{
if (input < min)
return (short)min;
if (input > max)
return (short)max;
return (short)input;
}
}
}

View File

@ -16,6 +16,8 @@ namespace ArdupilotMega.Antenna
int TiltStartRange { get; set; }
int PanEndRange { get; set; }
int TiltEndRange { get; set; }
int PanPWMRange { get; set; }
int TiltPWMRange { get; set; }
bool PanReverse { get; set; }
bool TiltReverse { get; set; }

View File

@ -21,6 +21,8 @@ namespace ArdupilotMega.Antenna
public int TiltStartRange { get; set; }
public int PanEndRange { get; set; }
public int TiltEndRange { get; set; }
public int PanPWMRange { get; set; }
public int TiltPWMRange { get; set; }
public bool PanReverse { get { return _panreverse == -1; } set { _panreverse = value == true ? -1 : 1 ; } }
public bool TiltReverse { get { return _tiltreverse == -1; } set { _tiltreverse = value == true ? -1 : 1; } }

View File

@ -33,7 +33,6 @@
this.label1 = new System.Windows.Forms.Label();
this.CMB_baudrate = new System.Windows.Forms.ComboBox();
this.CMB_serialport = new System.Windows.Forms.ComboBox();
this.BUT_connect = new ArdupilotMega.MyButton();
this.TRK_pantrim = new System.Windows.Forms.TrackBar();
this.TXT_panrange = new System.Windows.Forms.TextBox();
this.label3 = new System.Windows.Forms.Label();
@ -44,6 +43,18 @@
this.TRK_tilttrim = new System.Windows.Forms.TrackBar();
this.label2 = new System.Windows.Forms.Label();
this.label7 = new System.Windows.Forms.Label();
this.CHK_revpan = new System.Windows.Forms.CheckBox();
this.CHK_revtilt = new System.Windows.Forms.CheckBox();
this.TXT_pwmrangepan = new System.Windows.Forms.TextBox();
this.TXT_pwmrangetilt = new System.Windows.Forms.TextBox();
this.label8 = new System.Windows.Forms.Label();
this.label9 = new System.Windows.Forms.Label();
this.label10 = new System.Windows.Forms.Label();
this.label11 = new System.Windows.Forms.Label();
this.label12 = new System.Windows.Forms.Label();
this.BUT_connect = new ArdupilotMega.MyButton();
this.LBL_pantrim = new System.Windows.Forms.Label();
this.LBL_tilttrim = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).BeginInit();
this.SuspendLayout();
@ -52,7 +63,8 @@
//
this.CMB_interface.FormattingEnabled = true;
this.CMB_interface.Items.AddRange(new object[] {
"Maestro"});
"Maestro",
"ArduTracker"});
this.CMB_interface.Location = new System.Drawing.Point(83, 10);
this.CMB_interface.Name = "CMB_interface";
this.CMB_interface.Size = new System.Drawing.Size(121, 21);
@ -95,19 +107,9 @@
this.CMB_serialport.Size = new System.Drawing.Size(121, 21);
this.CMB_serialport.TabIndex = 1;
//
// BUT_connect
//
this.BUT_connect.Location = new System.Drawing.Point(476, 9);
this.BUT_connect.Name = "BUT_connect";
this.BUT_connect.Size = new System.Drawing.Size(75, 23);
this.BUT_connect.TabIndex = 3;
this.BUT_connect.Text = "Connect";
this.BUT_connect.UseVisualStyleBackColor = true;
this.BUT_connect.Click += new System.EventHandler(this.BUT_connect_Click);
//
// TRK_pantrim
//
this.TRK_pantrim.Location = new System.Drawing.Point(153, 65);
this.TRK_pantrim.Location = new System.Drawing.Point(153, 81);
this.TRK_pantrim.Maximum = 90;
this.TRK_pantrim.Minimum = -90;
this.TRK_pantrim.Name = "TRK_pantrim";
@ -118,7 +120,7 @@
//
// TXT_panrange
//
this.TXT_panrange.Location = new System.Drawing.Point(83, 65);
this.TXT_panrange.Location = new System.Drawing.Point(83, 81);
this.TXT_panrange.Name = "TXT_panrange";
this.TXT_panrange.Size = new System.Drawing.Size(64, 20);
this.TXT_panrange.TabIndex = 4;
@ -128,7 +130,7 @@
// label3
//
this.label3.AutoSize = true;
this.label3.Location = new System.Drawing.Point(326, 49);
this.label3.Location = new System.Drawing.Point(326, 65);
this.label3.Name = "label3";
this.label3.Size = new System.Drawing.Size(27, 13);
this.label3.TabIndex = 10;
@ -137,25 +139,25 @@
// label4
//
this.label4.AutoSize = true;
this.label4.Location = new System.Drawing.Point(83, 49);
this.label4.Location = new System.Drawing.Point(83, 65);
this.label4.Name = "label4";
this.label4.Size = new System.Drawing.Size(56, 13);
this.label4.Size = new System.Drawing.Size(39, 13);
this.label4.TabIndex = 11;
this.label4.Text = "Range -/+";
this.label4.Text = "Range";
//
// label5
//
this.label5.AutoSize = true;
this.label5.Location = new System.Drawing.Point(83, 125);
this.label5.Location = new System.Drawing.Point(83, 141);
this.label5.Name = "label5";
this.label5.Size = new System.Drawing.Size(56, 13);
this.label5.Size = new System.Drawing.Size(39, 13);
this.label5.TabIndex = 17;
this.label5.Text = "Range -/+";
this.label5.Text = "Range";
//
// label6
//
this.label6.AutoSize = true;
this.label6.Location = new System.Drawing.Point(326, 125);
this.label6.Location = new System.Drawing.Point(326, 141);
this.label6.Name = "label6";
this.label6.Size = new System.Drawing.Size(27, 13);
this.label6.TabIndex = 16;
@ -163,7 +165,7 @@
//
// TXT_tiltrange
//
this.TXT_tiltrange.Location = new System.Drawing.Point(83, 141);
this.TXT_tiltrange.Location = new System.Drawing.Point(83, 157);
this.TXT_tiltrange.Name = "TXT_tiltrange";
this.TXT_tiltrange.Size = new System.Drawing.Size(64, 20);
this.TXT_tiltrange.TabIndex = 6;
@ -172,7 +174,7 @@
//
// TRK_tilttrim
//
this.TRK_tilttrim.Location = new System.Drawing.Point(153, 141);
this.TRK_tilttrim.Location = new System.Drawing.Point(153, 157);
this.TRK_tilttrim.Maximum = 45;
this.TRK_tilttrim.Minimum = -45;
this.TRK_tilttrim.Name = "TRK_tilttrim";
@ -184,7 +186,7 @@
// label2
//
this.label2.AutoSize = true;
this.label2.Location = new System.Drawing.Point(13, 68);
this.label2.Location = new System.Drawing.Point(12, 65);
this.label2.Name = "label2";
this.label2.Size = new System.Drawing.Size(26, 13);
this.label2.TabIndex = 18;
@ -193,17 +195,140 @@
// label7
//
this.label7.AutoSize = true;
this.label7.Location = new System.Drawing.Point(13, 144);
this.label7.Location = new System.Drawing.Point(12, 141);
this.label7.Name = "label7";
this.label7.Size = new System.Drawing.Size(21, 13);
this.label7.TabIndex = 19;
this.label7.Text = "Tilt";
//
// CHK_revpan
//
this.CHK_revpan.AutoSize = true;
this.CHK_revpan.Location = new System.Drawing.Point(534, 83);
this.CHK_revpan.Name = "CHK_revpan";
this.CHK_revpan.Size = new System.Drawing.Size(46, 17);
this.CHK_revpan.TabIndex = 20;
this.CHK_revpan.Text = "Rev";
this.CHK_revpan.UseVisualStyleBackColor = true;
this.CHK_revpan.CheckedChanged += new System.EventHandler(this.CHK_revpan_CheckedChanged);
//
// CHK_revtilt
//
this.CHK_revtilt.AutoSize = true;
this.CHK_revtilt.Location = new System.Drawing.Point(534, 159);
this.CHK_revtilt.Name = "CHK_revtilt";
this.CHK_revtilt.Size = new System.Drawing.Size(46, 17);
this.CHK_revtilt.TabIndex = 21;
this.CHK_revtilt.Text = "Rev";
this.CHK_revtilt.UseVisualStyleBackColor = true;
this.CHK_revtilt.CheckedChanged += new System.EventHandler(this.CHK_revtilt_CheckedChanged);
//
// TXT_pwmrangepan
//
this.TXT_pwmrangepan.Location = new System.Drawing.Point(83, 107);
this.TXT_pwmrangepan.Name = "TXT_pwmrangepan";
this.TXT_pwmrangepan.Size = new System.Drawing.Size(64, 20);
this.TXT_pwmrangepan.TabIndex = 22;
this.TXT_pwmrangepan.Text = "1000";
//
// TXT_pwmrangetilt
//
this.TXT_pwmrangetilt.Location = new System.Drawing.Point(83, 183);
this.TXT_pwmrangetilt.Name = "TXT_pwmrangetilt";
this.TXT_pwmrangetilt.Size = new System.Drawing.Size(64, 20);
this.TXT_pwmrangetilt.TabIndex = 23;
this.TXT_pwmrangetilt.Text = "1000";
//
// label8
//
this.label8.AutoSize = true;
this.label8.Location = new System.Drawing.Point(43, 110);
this.label8.Name = "label8";
this.label8.Size = new System.Drawing.Size(34, 13);
this.label8.TabIndex = 24;
this.label8.Text = "PWM";
//
// label9
//
this.label9.AutoSize = true;
this.label9.Location = new System.Drawing.Point(43, 186);
this.label9.Name = "label9";
this.label9.Size = new System.Drawing.Size(34, 13);
this.label9.TabIndex = 25;
this.label9.Text = "PWM";
//
// label10
//
this.label10.AutoSize = true;
this.label10.Location = new System.Drawing.Point(45, 160);
this.label10.Name = "label10";
this.label10.Size = new System.Drawing.Size(34, 13);
this.label10.TabIndex = 27;
this.label10.Text = "Angle";
//
// label11
//
this.label11.AutoSize = true;
this.label11.Location = new System.Drawing.Point(45, 84);
this.label11.Name = "label11";
this.label11.Size = new System.Drawing.Size(34, 13);
this.label11.TabIndex = 26;
this.label11.Text = "Angle";
//
// label12
//
this.label12.AutoSize = true;
this.label12.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Bold, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
this.label12.Location = new System.Drawing.Point(94, 40);
this.label12.Name = "label12";
this.label12.Size = new System.Drawing.Size(403, 13);
this.label12.TabIndex = 28;
this.label12.Text = "Miss using this interface can cause servo damage, use with caution!!!";
//
// BUT_connect
//
this.BUT_connect.Location = new System.Drawing.Point(476, 9);
this.BUT_connect.Name = "BUT_connect";
this.BUT_connect.Size = new System.Drawing.Size(75, 23);
this.BUT_connect.TabIndex = 3;
this.BUT_connect.Text = "Connect";
this.BUT_connect.UseVisualStyleBackColor = true;
this.BUT_connect.Click += new System.EventHandler(this.BUT_connect_Click);
//
// LBL_pantrim
//
this.LBL_pantrim.AutoSize = true;
this.LBL_pantrim.Location = new System.Drawing.Point(326, 113);
this.LBL_pantrim.Name = "LBL_pantrim";
this.LBL_pantrim.Size = new System.Drawing.Size(34, 13);
this.LBL_pantrim.TabIndex = 29;
this.LBL_pantrim.Text = "Angle";
//
// LBL_tilttrim
//
this.LBL_tilttrim.AutoSize = true;
this.LBL_tilttrim.Location = new System.Drawing.Point(326, 190);
this.LBL_tilttrim.Name = "LBL_tilttrim";
this.LBL_tilttrim.Size = new System.Drawing.Size(34, 13);
this.LBL_tilttrim.TabIndex = 30;
this.LBL_tilttrim.Text = "Angle";
//
// 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.ClientSize = new System.Drawing.Size(587, 212);
this.Controls.Add(this.LBL_tilttrim);
this.Controls.Add(this.LBL_pantrim);
this.Controls.Add(this.label12);
this.Controls.Add(this.label10);
this.Controls.Add(this.label11);
this.Controls.Add(this.label9);
this.Controls.Add(this.label8);
this.Controls.Add(this.TXT_pwmrangetilt);
this.Controls.Add(this.TXT_pwmrangepan);
this.Controls.Add(this.CHK_revtilt);
this.Controls.Add(this.CHK_revpan);
this.Controls.Add(this.label7);
this.Controls.Add(this.label2);
this.Controls.Add(this.label5);
@ -222,6 +347,7 @@
this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
this.Name = "Tracker";
this.Text = "Tracker";
this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Tracker_FormClosing);
((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).EndInit();
this.ResumeLayout(false);
@ -246,5 +372,16 @@
private System.Windows.Forms.TrackBar TRK_tilttrim;
private System.Windows.Forms.Label label2;
private System.Windows.Forms.Label label7;
private System.Windows.Forms.CheckBox CHK_revpan;
private System.Windows.Forms.CheckBox CHK_revtilt;
private System.Windows.Forms.TextBox TXT_pwmrangepan;
private System.Windows.Forms.TextBox TXT_pwmrangetilt;
private System.Windows.Forms.Label label8;
private System.Windows.Forms.Label label9;
private System.Windows.Forms.Label label10;
private System.Windows.Forms.Label label11;
private System.Windows.Forms.Label label12;
private System.Windows.Forms.Label LBL_pantrim;
private System.Windows.Forms.Label LBL_tilttrim;
}
}

View File

@ -15,6 +15,12 @@ namespace ArdupilotMega.Antenna
static bool threadrun = false;
static ITrackerOutput tracker;
enum interfaces
{
Maestro,
ArduTracker
}
public Tracker()
{
InitializeComponent();
@ -27,10 +33,63 @@ namespace ArdupilotMega.Antenna
{
BUT_connect.Text = "Disconnect";
}
foreach (string value in MainV2.config.Keys)
{
if (value.StartsWith("Tracker_"))
{
var ctls = Controls.Find(value.Replace("Tracker_",""),true);
foreach (Control ctl in ctls)
{
if (typeof(TextBox) == ctl.GetType() ||
typeof(ComboBox) == ctl.GetType())
{
ctl.Text = MainV2.config[value].ToString();
}
else if (typeof(TrackBar) == ctl.GetType())
{
((TrackBar)ctl).Value = int.Parse(MainV2.config[value].ToString());
}
else if (typeof(CheckBox) == ctl.GetType())
{
((CheckBox)ctl).Checked = bool.Parse(MainV2.config[value].ToString());
}
}
}
}
// update other fields from load params
TXT_panrange_TextChanged(null, null);
TXT_tiltrange_TextChanged(null, null);
TRK_pantrim_Scroll(null, null);
TRK_tilttrim_Scroll(null, null);
}
void saveconfig()
{
foreach (Control ctl in Controls)
{
if (typeof(TextBox) == ctl.GetType() ||
typeof(ComboBox) == ctl.GetType())
{
MainV2.config["Tracker_" + ctl.Name] = ctl.Text;
}
if (typeof(TrackBar) == ctl.GetType())
{
MainV2.config["Tracker_" + ctl.Name] = ((TrackBar)ctl).Value;
}
if (typeof(CheckBox) == ctl.GetType())
{
MainV2.config["Tracker_" + ctl.Name] = ((CheckBox)ctl).Checked;
}
}
}
private void BUT_connect_Click(object sender, EventArgs e)
{
saveconfig();
if (threadrun)
{
threadrun = false;
@ -44,7 +103,10 @@ namespace ArdupilotMega.Antenna
tracker.ComPort.Close();
}
if (CMB_interface.Text == "Maestro")
tracker = new ArdupilotMega.Antenna.Maestro();
if (CMB_interface.Text == "ArduTracker")
tracker = new ArdupilotMega.Antenna.ArduTracker();
try
{
@ -58,14 +120,20 @@ namespace ArdupilotMega.Antenna
try
{
tracker.PanStartRange = int.Parse(TXT_panrange.Text) / 2 * -1;
tracker.PanEndRange = int.Parse(TXT_panrange.Text) / 2;
tracker.PanStartRange = int.Parse(TXT_panrange.Text) / 1 * -1;
tracker.PanEndRange = int.Parse(TXT_panrange.Text) / 1;
tracker.TrimPan = TRK_pantrim.Value;
tracker.TiltStartRange = int.Parse(TXT_tiltrange.Text) / 2 * -1;
tracker.TiltEndRange = int.Parse(TXT_tiltrange.Text) / 2;
tracker.TrimTilt = TRK_tilttrim.Value;
tracker.PanReverse = CHK_revpan.Checked;
tracker.TiltReverse = CHK_revtilt.Checked;
tracker.PanPWMRange = int.Parse(TXT_pwmrangepan.Text);
tracker.TiltPWMRange = int.Parse(TXT_pwmrangetilt.Text);
}
catch (Exception ex) { CustomMessageBox.Show("Bad User input " + ex.Message); return; }
@ -83,6 +151,8 @@ namespace ArdupilotMega.Antenna
t12.Start();
}
}
BUT_connect.Text = "Disconnect";
}
void mainloop()
@ -104,12 +174,14 @@ namespace ArdupilotMega.Antenna
{
if (tracker != null)
tracker.TrimPan = TRK_pantrim.Value;
LBL_pantrim.Text = TRK_pantrim.Value.ToString();
}
private void TRK_tilttrim_Scroll(object sender, EventArgs e)
{
if (tracker != null)
tracker.TrimTilt = TRK_tilttrim.Value;
LBL_tilttrim.Text = TRK_tilttrim.Value.ToString();
}
private void TXT_panrange_TextChanged(object sender, EventArgs e)
@ -118,8 +190,8 @@ namespace ArdupilotMega.Antenna
int.TryParse(TXT_panrange.Text, out range);
TRK_pantrim.Minimum = range / 2 * -1;
TRK_pantrim.Maximum = range / 2;
TRK_pantrim.Minimum = range / 1 * -1;
TRK_pantrim.Maximum = range / 1;
}
private void TXT_tiltrange_TextChanged(object sender, EventArgs e)
@ -128,8 +200,23 @@ namespace ArdupilotMega.Antenna
int.TryParse(TXT_tiltrange.Text, out range);
TRK_tilttrim.Minimum = range / 2 * -1;
TRK_tilttrim.Maximum = range / 2;
TRK_tilttrim.Minimum = range / 1 * -1;
TRK_tilttrim.Maximum = range / 1;
}
private void CHK_revpan_CheckedChanged(object sender, EventArgs e)
{
}
private void CHK_revtilt_CheckedChanged(object sender, EventArgs e)
{
}
private void Tracker_FormClosing(object sender, FormClosingEventArgs e)
{
saveconfig();
}
}
}

View File

@ -213,6 +213,7 @@
</Reference>
</ItemGroup>
<ItemGroup>
<Compile Include="Antenna\ArduTracker.cs" />
<Compile Include="Antenna\ITrackerOutput.cs" />
<Compile Include="Antenna\Maestro.cs" />
<Compile Include="Antenna\Tracker.cs">
@ -230,6 +231,7 @@
<DependentUpon>ProgressReporterDialogue.cs</DependentUpon>
</Compile>
<Compile Include="MagCalib.cs" />
<Compile Include="PIDTunning.cs" />
<Compile Include="Radio\3DRradio.cs">
<SubType>Form</SubType>
</Compile>
@ -446,7 +448,6 @@
</Compile>
<Compile Include="Radio\Uploader.cs" />
<Compile Include="LangUtility.cs" />
<Compile Include="test.cs" />
<Compile Include="ThemeManager.cs" />
<EmbeddedResource Include="Antenna\Tracker.resx">
<DependentUpon>Tracker.cs</DependentUpon>

View File

@ -3,6 +3,7 @@ using System.Collections.Generic;
using System.Text;
using System.IO.Ports;
using System.IO;
using System.Linq;
namespace ArdupilotMega
{
@ -18,6 +19,11 @@ namespace ArdupilotMega
public void toggleDTR()
{
bool open = this.IsOpen;
if (!open)
this.Open();
base.DtrEnable = false;
base.RtsEnable = false;
@ -27,6 +33,56 @@ namespace ArdupilotMega
base.RtsEnable = true;
System.Threading.Thread.Sleep(50);
if (!open)
this.Close();
}
public new static string[] GetPortNames()
{
string[] monoDevs = new string[0];
if (Directory.Exists("/dev/"))
{
if (Directory.Exists("/dev/serial/by-id/"))
monoDevs = Directory.GetFiles("/dev/serial/by-id/", "*");
monoDevs = Directory.GetFiles("/dev/", "*ACM*");
monoDevs = Directory.GetFiles("/dev/", "ttyUSB*");
}
string[] ports = System.IO.Ports.SerialPort.GetPortNames()
.Select(p => p.TrimEnd())
.Select(FixBlueToothPortNameBug)
.ToArray();
string[] allPorts = new string[monoDevs.Length + ports.Length];
monoDevs.CopyTo(allPorts, 0);
ports.CopyTo(allPorts, monoDevs.Length);
return allPorts;
}
// .NET bug: sometimes bluetooth ports are enumerated with bogus characters
// eg 'COM10' becomes 'COM10c' - one workaround is to remove the non numeric
// char. Annoyingly, sometimes a numeric char is added, which means this
// does not work in all cases.
// See http://connect.microsoft.com/VisualStudio/feedback/details/236183/system-io-ports-serialport-getportnames-error-with-bluetooth
private static string FixBlueToothPortNameBug(string portName)
{
if (!portName.StartsWith("COM"))
return portName;
var newPortName = "COM"; // Start over with "COM"
foreach (var portChar in portName.Substring(3).ToCharArray()) // Remove "COM", put the rest in a character array
{
if (char.IsDigit(portChar))
newPortName += portChar.ToString(); // Good character, append to portName
// else
//log.WarnFormat("Bad (Non Numeric) character in port name '{0}' - removing", portName);
}
return newPortName;
}
}
}

View File

@ -792,7 +792,7 @@ namespace ArdupilotMega.GCSViews
try
{
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
swlog = new StreamWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm") + " telem.log");
swlog = new StreamWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm") + " telem.log");
}
catch { CustomMessageBox.Show("Log creation error"); }
}
@ -1375,7 +1375,7 @@ namespace ArdupilotMega.GCSViews
aviwriter = new AviWriter();
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
aviwriter.avi_start(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm-ss") + ".avi");
aviwriter.avi_start(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".avi");
recordHudToAVIToolStripMenuItem.Text = "Recording";
}

View File

@ -233,7 +233,7 @@ namespace ArdupilotMega
case serialstatus.Createfile:
receivedbytes = 0;
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
logfile = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm") + " " + currentlog + ".log";
logfile = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm") + " " + currentlog + ".log";
sw = new StreamWriter(logfile);
status = serialstatus.Waiting;
lock (thisLock)

View File

@ -184,9 +184,6 @@ namespace ArdupilotMega
BaseStream.DiscardInBuffer();
// removed because of apc220 units
//BaseStream.toggleDTR();
Thread.Sleep(1000);
}

View File

@ -117,7 +117,7 @@ namespace ArdupilotMega
comPort.BaseStream.BaudRate = 115200;
CMB_serialport.Items.AddRange(GetPortNames());
CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
CMB_serialport.Items.Add("TCP");
CMB_serialport.Items.Add("UDP");
if (CMB_serialport.Items.Count > 0)
@ -253,57 +253,6 @@ namespace ArdupilotMega
splash.Close();
}
private string[] GetPortNames()
{
string[] monoDevs = new string[0];
log.Debug("Getting Comports");
if (MONO)
{
if (Directory.Exists("/dev/"))
{
if (Directory.Exists("/dev/serial/by-id/"))
monoDevs = Directory.GetFiles("/dev/serial/by-id/", "*");
monoDevs = Directory.GetFiles("/dev/", "*ACM*");
monoDevs = Directory.GetFiles("/dev/", "ttyUSB*");
}
}
string[] ports = SerialPort.GetPortNames()
.Select(p => p.TrimEnd())
.Select(FixBlueToothPortNameBug)
.ToArray();
string[] allPorts = new string[monoDevs.Length + ports.Length];
monoDevs.CopyTo(allPorts, 0);
ports.CopyTo(allPorts, monoDevs.Length);
return allPorts;
}
// .NET bug: sometimes bluetooth ports are enumerated with bogus characters
// eg 'COM10' becomes 'COM10c' - one workaround is to remove the non numeric
// char. Annoyingly, sometimes a numeric char is added, which means this
// does not work in all cases.
// See http://connect.microsoft.com/VisualStudio/feedback/details/236183/system-io-ports-serialport-getportnames-error-with-bluetooth
private string FixBlueToothPortNameBug(string portName)
{
if (!portName.StartsWith("COM"))
return portName;
var newPortName = "COM"; // Start over with "COM"
foreach (var portChar in portName.Substring(3).ToCharArray()) // Remove "COM", put the rest in a character array
{
if (char.IsDigit(portChar))
newPortName += portChar.ToString(); // Good character, append to portName
else
log.WarnFormat("Bad (Non Numeric) character in port name '{0}' - removing", portName);
}
return newPortName;
}
internal void ScreenShot()
{
Rectangle bounds = Screen.GetBounds(Point.Empty);
@ -313,7 +262,7 @@ namespace ArdupilotMega
{
g.CopyFromScreen(Point.Empty, Point.Empty, bounds.Size);
}
string name = "ss" + DateTime.Now.ToString("hhmmss") + ".jpg";
string name = "ss" + DateTime.Now.ToString("HHmmss") + ".jpg";
bitmap.Save(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + name, System.Drawing.Imaging.ImageFormat.Jpeg);
CustomMessageBox.Show("Screenshot saved to " + name);
}
@ -324,7 +273,7 @@ namespace ArdupilotMega
{
string oldport = CMB_serialport.Text;
CMB_serialport.Items.Clear();
CMB_serialport.Items.AddRange(GetPortNames());
CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
CMB_serialport.Items.Add("TCP");
CMB_serialport.Items.Add("UDP");
if (CMB_serialport.Items.Contains(oldport))
@ -538,10 +487,19 @@ namespace ArdupilotMega
comPort.BaseStream.StopBits = (StopBits)Enum.Parse(typeof(StopBits), "1");
comPort.BaseStream.Parity = (Parity)Enum.Parse(typeof(Parity), "None");
comPort.BaseStream.DtrEnable = false;
try
{
comPort.BaseStream.PortName = CMB_serialport.Text;
// false here
comPort.BaseStream.DtrEnable = false;
comPort.BaseStream.RtsEnable = false;
if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true)
comPort.BaseStream.toggleDTR();
// if reset on connect is on dtr will be true here
if (comPort.logfile != null)
comPort.logfile.Close();
try
@ -551,7 +509,6 @@ namespace ArdupilotMega
}
catch { CustomMessageBox.Show("Failed to create log - wont log this session"); } // soft fail
comPort.BaseStream.PortName = CMB_serialport.Text;
comPort.Open(true);
if (comPort.param["SYSID_SW_TYPE"] != null)

View File

@ -0,0 +1,46 @@
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
namespace ArdupilotMega
{
class PIDTunning
{
public static void twiddle(double[] initialgains, Func<double[],double> run, double tol = 0.001)
{
int n_params = 3;
double err= 0;
double[] dparams = initialgains; //{1.0f,1.0f,1.0f};
double[] paramss = {0.0f,0.0f,0.0f};
double best_error = run(paramss);
int n = 0;
while (dparams.Sum() > tol) {
for (int i = 0; i < n_params; i++){
paramss[i] += dparams[i];
err = run(paramss);
if (err < best_error){
best_error = err;
dparams[i] *= 1.1;
}
else {
paramss[i] -= 2.0 * dparams[i];
err = run(paramss);
if (err < best_error){
best_error = err;
dparams[i] *= 1.1;
}
else {
paramss[i] += dparams[i];
dparams[i] *= 0.9;
}
}
n += 1;
Console.WriteLine("Twiddle #" + n + " " + paramss.ToString() + " -> " + best_error);
}
}
}
}
}

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