forked from ArduPilot/MissionPlanner
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathTracker.cs
353 lines (282 loc) · 10.9 KB
/
Tracker.cs
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
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;
using MissionPlanner.Controls;
using MissionPlanner.Comms;
using MissionPlanner.Utilities;
namespace MissionPlanner.Antenna
{
public partial class Tracker : UserControl, IDeactivate
{
System.Threading.Thread t12;
static bool threadrun = false;
static ITrackerOutput tracker;
enum interfaces
{
Maestro,
ArduTracker,
DegreeTracker
}
public Tracker()
{
InitializeComponent();
ThemeManager.ApplyThemeTo(this);
CMB_serialport.DataSource = SerialPort.GetPortNames();
if (threadrun)
{
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;
BUT_connect.Text = "Connect";
tracker.Close();
foreach (Control ctl in Controls)
{
if (ctl.Name.StartsWith("TXT_"))
ctl.Enabled = true;
if (ctl.Name.StartsWith("CMB_"))
ctl.Enabled = true;
}
BUT_find.Enabled = true;
//CustomMessageBox.Show("Disconnected!");
return;
}
if (tracker != null && tracker.ComPort != null && tracker.ComPort.IsOpen)
{
tracker.ComPort.Close();
}
if (CMB_interface.Text == interfaces.Maestro.ToString())
tracker = new Antenna.Maestro();
if (CMB_interface.Text == interfaces.ArduTracker.ToString())
tracker = new Antenna.ArduTracker();
if (CMB_interface.Text == interfaces.DegreeTracker.ToString())
tracker = new Antenna.DegreeTracker();
try
{
tracker.ComPort = new SerialPort()
{
PortName = CMB_serialport.Text,
BaudRate = int.Parse(CMB_baudrate.Text)
};
}
catch (Exception ex) { CustomMessageBox.Show("Bad Port settings " + ex.Message,"Error"); return; }
try
{
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_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);
tracker.PanPWMCenter = int.Parse(TXT_centerpan.Text);
tracker.TiltPWMCenter = int.Parse(TXT_centertilt.Text);
}
catch (Exception ex) { CustomMessageBox.Show("Bad User input " + ex.Message,"Error"); return; }
if (tracker.Init())
{
if (tracker.Setup())
{
if (TXT_centerpan.Text != tracker.PanPWMCenter.ToString())
TXT_centerpan.Text = tracker.PanPWMCenter.ToString();
if (TXT_centertilt.Text != tracker.TiltPWMCenter.ToString())
TXT_centertilt.Text = tracker.TiltPWMCenter.ToString();
tracker.PanAndTilt(0, 0);
foreach (Control ctl in Controls)
{
if(ctl.Name.StartsWith("TXT_"))
ctl.Enabled = false;
if (ctl.Name.StartsWith("CMB_"))
ctl.Enabled = false;
}
//BUT_find.Enabled = false;
t12 = new System.Threading.Thread(new System.Threading.ThreadStart(mainloop))
{
IsBackground = true,
Name = "Antenna Tracker"
};
t12.Start();
}
}
BUT_connect.Text = "Disconnect";
}
void mainloop()
{
threadrun = true;
while (threadrun)
{
try
{
// 10 hz - position updates default to 3 hz on the stream rate
tracker.PanAndTilt(MainV2.comPort.MAV.cs.AZToMAV, MainV2.comPort.MAV.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;
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)
{
int range;
int.TryParse(TXT_panrange.Text, out range);
TRK_pantrim.Minimum = range / 2 * -1;
TRK_pantrim.Maximum = range / 2;
}
private void TXT_tiltrange_TextChanged(object sender, EventArgs e)
{
int range;
int.TryParse(TXT_tiltrange.Text, out range);
TRK_tilttrim.Minimum = range / 2 * -1;
TRK_tilttrim.Maximum = range / 2;
}
private void CHK_revpan_CheckedChanged(object sender, EventArgs e)
{
}
private void CHK_revtilt_CheckedChanged(object sender, EventArgs e)
{
}
public void Deactivate()
{
saveconfig();
}
private void BUT_find_Click(object sender, EventArgs e)
{
System.Threading.ThreadPool.QueueUserWorkItem(tm1_Tick);
}
void tm1_Tick(object item)
{
float snr = MainV2.comPort.MAV.cs.localsnrdb;
float best = snr;
float tilt = 0;
float pan = 0;
if (snr == 0)
{
CustomMessageBox.Show("No valid 3dr radio","Error");
return;
}
this.Invoke((MethodInvoker)delegate
{
tilt = TRK_tilttrim.Value;
pan = TRK_pantrim.Value;
});
// scan half range within 30 degrees
float ans = checkpos((pan - float.Parse(TXT_panrange.Text) / 4), (pan + float.Parse(TXT_panrange.Text) / 4) - 1, 30);
// scan new range within 30 - little overlap
ans = checkpos((-30 + ans), (30 + ans), 5);
// scan new range
ans = checkpos((-5 + ans), (5 + ans), 1);
setpan(ans);
}
void setpan(float no)
{
this.Invoke((MethodInvoker)delegate
{
try
{
TRK_pantrim.Value = (int)no;
TRK_pantrim_Scroll(null, null);
}
catch { return; }
});
}
float checkpos(float start, float end,float scale)
{
float lastsnr = 0;
float best = 0;
setpan(start);
System.Threading.Thread.Sleep(4000);
for (float n = start; n < end; n += scale)
{
setpan(n);
System.Threading.Thread.Sleep(2000);
Console.WriteLine("Angle " + n + " snr " + MainV2.comPort.MAV.cs.localsnrdb);
if (MainV2.comPort.MAV.cs.localsnrdb > lastsnr)
{
best = n;
lastsnr = MainV2.comPort.MAV.cs.localsnrdb;
}
}
return best;
}
private void CMB_interface_SelectedIndexChanged(object sender, EventArgs e)
{
}
private void TXT_centerpan_TextChanged(object sender, EventArgs e)
{
}
private void TXT_centertilt_TextChanged(object sender, EventArgs e)
{
}
}
}