2012-02-26 19:13:23 -04:00
|
|
|
|
using System;
|
|
|
|
|
using System.Collections.Generic;
|
|
|
|
|
using System.ComponentModel;
|
|
|
|
|
using System.Data;
|
|
|
|
|
using System.Drawing;
|
|
|
|
|
using System.Linq;
|
|
|
|
|
using System.Text;
|
|
|
|
|
using System.Windows.Forms;
|
2012-04-06 05:27:26 -03:00
|
|
|
|
using ArdupilotMega.Controls.BackstageView;
|
2012-02-26 19:13:23 -04:00
|
|
|
|
|
|
|
|
|
namespace ArdupilotMega.Antenna
|
|
|
|
|
{
|
2012-04-06 05:27:26 -03:00
|
|
|
|
public partial class Tracker : BackStageViewContentPanel
|
2012-02-26 19:13:23 -04:00
|
|
|
|
{
|
|
|
|
|
System.Threading.Thread t12;
|
|
|
|
|
static bool threadrun = false;
|
|
|
|
|
static ITrackerOutput tracker;
|
|
|
|
|
|
2012-03-23 09:52:12 -03:00
|
|
|
|
enum interfaces
|
|
|
|
|
{
|
|
|
|
|
Maestro,
|
|
|
|
|
ArduTracker
|
|
|
|
|
}
|
|
|
|
|
|
2012-02-26 19:13:23 -04:00
|
|
|
|
public Tracker()
|
|
|
|
|
{
|
|
|
|
|
InitializeComponent();
|
|
|
|
|
|
2012-03-03 20:42:42 -04:00
|
|
|
|
ThemeManager.ApplyThemeTo(this);
|
2012-02-26 19:13:23 -04:00
|
|
|
|
|
|
|
|
|
CMB_serialport.DataSource = SerialPort.GetPortNames();
|
|
|
|
|
|
|
|
|
|
if (threadrun)
|
|
|
|
|
{
|
|
|
|
|
BUT_connect.Text = "Disconnect";
|
|
|
|
|
}
|
2012-03-23 09:52:12 -03:00
|
|
|
|
|
|
|
|
|
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;
|
|
|
|
|
}
|
|
|
|
|
}
|
2012-02-26 19:13:23 -04:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void BUT_connect_Click(object sender, EventArgs e)
|
|
|
|
|
{
|
2012-03-23 09:52:12 -03:00
|
|
|
|
saveconfig();
|
|
|
|
|
|
2012-02-26 19:13:23 -04:00
|
|
|
|
if (threadrun)
|
|
|
|
|
{
|
|
|
|
|
threadrun = false;
|
|
|
|
|
BUT_connect.Text = "Connect";
|
|
|
|
|
tracker.Close();
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
|
2012-02-29 09:19:54 -04:00
|
|
|
|
if (tracker != null && tracker.ComPort != null && tracker.ComPort.IsOpen)
|
|
|
|
|
{
|
|
|
|
|
tracker.ComPort.Close();
|
|
|
|
|
}
|
|
|
|
|
|
2012-03-23 09:52:12 -03:00
|
|
|
|
if (CMB_interface.Text == "Maestro")
|
|
|
|
|
tracker = new ArdupilotMega.Antenna.Maestro();
|
|
|
|
|
if (CMB_interface.Text == "ArduTracker")
|
|
|
|
|
tracker = new ArdupilotMega.Antenna.ArduTracker();
|
2012-02-26 19:13:23 -04:00
|
|
|
|
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
tracker.ComPort = new SerialPort()
|
|
|
|
|
{
|
|
|
|
|
PortName = CMB_serialport.Text,
|
|
|
|
|
BaudRate = int.Parse(CMB_baudrate.Text)
|
|
|
|
|
};
|
|
|
|
|
}
|
2012-03-09 11:18:12 -04:00
|
|
|
|
catch (Exception ex) { CustomMessageBox.Show("Bad Port settings " + ex.Message); return; }
|
2012-02-26 19:13:23 -04:00
|
|
|
|
|
|
|
|
|
try
|
|
|
|
|
{
|
2012-03-29 19:17:06 -03:00
|
|
|
|
tracker.PanStartRange = int.Parse(TXT_panrange.Text) / 2 * -1;
|
|
|
|
|
tracker.PanEndRange = int.Parse(TXT_panrange.Text) / 2;
|
2012-02-26 19:13:23 -04:00
|
|
|
|
tracker.TrimPan = TRK_pantrim.Value;
|
|
|
|
|
|
2012-02-29 09:19:54 -04:00
|
|
|
|
tracker.TiltStartRange = int.Parse(TXT_tiltrange.Text) / 2 * -1;
|
|
|
|
|
tracker.TiltEndRange = int.Parse(TXT_tiltrange.Text) / 2;
|
2012-02-26 19:13:23 -04:00
|
|
|
|
tracker.TrimTilt = TRK_tilttrim.Value;
|
|
|
|
|
|
2012-03-23 09:52:12 -03:00
|
|
|
|
tracker.PanReverse = CHK_revpan.Checked;
|
|
|
|
|
tracker.TiltReverse = CHK_revtilt.Checked;
|
|
|
|
|
|
|
|
|
|
tracker.PanPWMRange = int.Parse(TXT_pwmrangepan.Text);
|
|
|
|
|
tracker.TiltPWMRange = int.Parse(TXT_pwmrangetilt.Text);
|
|
|
|
|
|
2012-02-26 19:13:23 -04:00
|
|
|
|
}
|
2012-03-09 11:18:12 -04:00
|
|
|
|
catch (Exception ex) { CustomMessageBox.Show("Bad User input " + ex.Message); return; }
|
2012-02-26 19:13:23 -04:00
|
|
|
|
|
|
|
|
|
if (tracker.Init())
|
|
|
|
|
{
|
|
|
|
|
if (tracker.Setup())
|
|
|
|
|
{
|
|
|
|
|
tracker.PanAndTilt(0, 0);
|
|
|
|
|
|
|
|
|
|
t12 = new System.Threading.Thread(new System.Threading.ThreadStart(mainloop))
|
|
|
|
|
{
|
|
|
|
|
IsBackground = true,
|
|
|
|
|
Name = "Antenna Tracker"
|
|
|
|
|
};
|
2012-02-29 09:19:54 -04:00
|
|
|
|
t12.Start();
|
2012-02-26 19:13:23 -04:00
|
|
|
|
}
|
|
|
|
|
}
|
2012-03-23 09:52:12 -03:00
|
|
|
|
|
|
|
|
|
BUT_connect.Text = "Disconnect";
|
2012-02-26 19:13:23 -04:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
void mainloop()
|
|
|
|
|
{
|
|
|
|
|
threadrun = true;
|
|
|
|
|
while (threadrun)
|
|
|
|
|
{
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
// 10 hz - position updates default to 3 hz on the stream rate
|
|
|
|
|
tracker.PanAndTilt(MainV2.cs.AZToMAV, MainV2.cs.ELToMAV);
|
|
|
|
|
System.Threading.Thread.Sleep(100);
|
|
|
|
|
}
|
|
|
|
|
catch { }
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void TRK_pantrim_Scroll(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
if (tracker != null)
|
|
|
|
|
tracker.TrimPan = TRK_pantrim.Value;
|
2012-03-23 09:52:12 -03:00
|
|
|
|
LBL_pantrim.Text = TRK_pantrim.Value.ToString();
|
2012-02-26 19:13:23 -04:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void TRK_tilttrim_Scroll(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
if (tracker != null)
|
|
|
|
|
tracker.TrimTilt = TRK_tilttrim.Value;
|
2012-03-23 09:52:12 -03:00
|
|
|
|
LBL_tilttrim.Text = TRK_tilttrim.Value.ToString();
|
2012-02-26 19:13:23 -04:00
|
|
|
|
}
|
2012-03-06 06:27:43 -04:00
|
|
|
|
|
|
|
|
|
private void TXT_panrange_TextChanged(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
int range;
|
|
|
|
|
|
|
|
|
|
int.TryParse(TXT_panrange.Text, out range);
|
|
|
|
|
|
2012-03-23 09:52:12 -03:00
|
|
|
|
TRK_pantrim.Minimum = range / 1 * -1;
|
|
|
|
|
TRK_pantrim.Maximum = range / 1;
|
2012-03-06 06:27:43 -04:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
private void TXT_tiltrange_TextChanged(object sender, EventArgs e)
|
|
|
|
|
{
|
|
|
|
|
int range;
|
|
|
|
|
|
|
|
|
|
int.TryParse(TXT_tiltrange.Text, out range);
|
|
|
|
|
|
2012-03-23 09:52:12 -03:00
|
|
|
|
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();
|
2012-03-06 06:27:43 -04:00
|
|
|
|
}
|
2012-02-26 19:13:23 -04:00
|
|
|
|
}
|
|
|
|
|
}
|