forked from ArduPilot/MissionPlanner
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy path3DRradio.cs
800 lines (635 loc) · 26.1 KB
/
3DRradio.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
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
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 System.Net;
using System.IO;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Arduino;
using ArdupilotMega.Comms;
using log4net;
using System.Reflection;
using System.Text.RegularExpressions;
namespace ArdupilotMega
{
public partial class _3DRradio : UserControl
{
public delegate void LogEventHandler(string message, int level = 0);
public delegate void ProgressEventHandler(double completed);
string firmwarefile = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "radio.hex";
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
public _3DRradio()
{
InitializeComponent();
// hide advanced view
//SPLIT_local.Panel2Collapsed = true;
//SPLIT_remote.Panel2Collapsed = true;
// setup netid
S3.DataSource = Enumerable.Range(0, 500).ToArray();
RS3.DataSource = Enumerable.Range(0, 500).ToArray();
}
bool getFirmware(uploader.Uploader.Code device)
{
// was https://raw.github.com/tridge/SiK/master/Firmware/dst/radio.hm_trp.hex
// now http://www.samba.org/tridge/UAV/3DR/radio.hm_trp.hex
if (device == uploader.Uploader.Code.DEVICE_ID_HM_TRP)
{
return Common.getFilefromNet("http://www.samba.org/tridge/UAV/3DR/radio.hm_trp.hex", firmwarefile);
}
else if (device == uploader.Uploader.Code.DEVICE_ID_RFD900)
{
return Common.getFilefromNet("http://rfdesign.com.au/firmware/radio.rfd900.hex", firmwarefile);
}
else if (device == uploader.Uploader.Code.DEVICE_ID_RFD900A)
{
return Common.getFilefromNet("http://rfdesign.com.au/firmware/radio.rfd900a.hex", firmwarefile);
}
else
{
return false;
}
}
void Sleep(int mstimeout)
{
DateTime endtime = DateTime.Now.AddMilliseconds(mstimeout);
while (DateTime.Now < endtime)
{
System.Threading.Thread.Sleep(1);
Application.DoEvents();
}
}
private void BUT_upload_Click(object sender, EventArgs e)
{
ArduinoSTK comPort = new ArduinoSTK();
uploader.Uploader uploader = new uploader.Uploader();
try
{
comPort.PortName = MainV2.comPort.BaseStream.PortName;
comPort.BaudRate = 115200;
comPort.Open();
}
catch { CustomMessageBox.Show("Invalid ComPort or in use"); return; }
bool bootloadermode = false;
// attempt bootloader mode
try
{
uploader_ProgressEvent(0);
uploader_LogEvent("Trying Bootloader Mode");
uploader.port = comPort;
uploader.connect_and_sync();
uploader.ProgressEvent += new ProgressEventHandler(uploader_ProgressEvent);
uploader.LogEvent += new LogEventHandler(uploader_LogEvent);
uploader_LogEvent("In Bootloader Mode");
bootloadermode = true;
}
catch
{
// cleanup bootloader mode fail, and try firmware mode
comPort.Close();
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
comPort.Open();
uploader.ProgressEvent += new ProgressEventHandler(uploader_ProgressEvent);
uploader.LogEvent += new LogEventHandler(uploader_LogEvent);
uploader_LogEvent("Trying Firmware Mode");
bootloadermode = false;
}
// check for either already bootloadermode, or if we can do a ATI to ID the firmware
if (bootloadermode || doConnect(comPort))
{
uploader.IHex iHex = new uploader.IHex();
iHex.LogEvent += new LogEventHandler(iHex_LogEvent);
iHex.ProgressEvent += new ProgressEventHandler(iHex_ProgressEvent);
// put into bootloader mode/udpate mode
if (!bootloadermode)
{
try
{
comPort.Write("AT&UPDATE\r\n");
string left = comPort.ReadExisting();
log.Info(left);
Sleep(700);
comPort.BaudRate = 115200;
}
catch { }
}
global::uploader.Uploader.Code device = global::uploader.Uploader.Code.FAILED;
global::uploader.Uploader.Code freq = global::uploader.Uploader.Code.FAILED;
// get the device type and frequency in the bootloader
uploader.getDevice(ref device, ref freq);
// get firmware for this device
if (getFirmware(device))
{
// load the hex
try
{
iHex.load(firmwarefile);
}
catch { CustomMessageBox.Show("Bad Firmware File"); goto exit; }
// upload the hex and verify
try
{
uploader.upload(comPort, iHex);
}
catch (Exception ex) { CustomMessageBox.Show("Upload Failed " + ex.Message); }
}
else
{
CustomMessageBox.Show("Failed to download new firmware");
}
}
else
{
CustomMessageBox.Show("Failed to identify Radio");
}
exit:
if (comPort.IsOpen)
comPort.Close();
}
void iHex_ProgressEvent(double completed)
{
try
{
Progressbar.Value = (int)(completed * 100);
Application.DoEvents();
}
catch { }
}
void uploader_LogEvent(string message, int level = 0)
{
try
{
if (level == 0)
{
Console.Write(message);
lbl_status.Text = message;
log.Info(message);
Application.DoEvents();
}
else if (level < 5) // 5 = byte data
{
log.Debug(message);
}
}
catch { }
}
void iHex_LogEvent(string message, int level = 0)
{
try
{
if (level == 0)
{
lbl_status.Text = message;
Console.WriteLine(message);
log.Info(message);
Application.DoEvents();
}
}
catch { }
}
void uploader_ProgressEvent(double completed)
{
try
{
Progressbar.Value = (int)(completed * 100);
Application.DoEvents();
}
catch { }
}
private void BUT_savesettings_Click(object sender, EventArgs e)
{
ArdupilotMega.Comms.ICommsSerial comPort = new SerialPort();
try
{
comPort.PortName = MainV2.comPort.BaseStream.PortName;
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
comPort.ReadTimeout = 4000;
comPort.Open();
}
catch { CustomMessageBox.Show("Invalid ComPort or in use"); return; }
lbl_status.Text = "Connecting";
if (doConnect(comPort))
{
// cleanup
doCommand(comPort, "AT&T");
comPort.DiscardInBuffer();
lbl_status.Text = "Doing Command";
if (RTI.Text != "")
{
// remote
string answer = doCommand(comPort, "RTI5");
string[] items = answer.Split('\n');
foreach (string item in items)
{
if (item.StartsWith("S"))
{
string[] values = item.Split(':', '=');
if (values.Length == 3)
{
Control[] controls = this.Controls.Find("R" + values[0].Trim(), true);
if (controls.Length > 0)
{
if (controls[0].GetType() == typeof(CheckBox))
{
string value = ((CheckBox)controls[0]).Checked ? "1" : "0";
if (value != values[2].Trim())
{
string cmdanswer = doCommand(comPort, "RT" + values[0].Trim() + "=" + value + "\r");
if (cmdanswer.Contains("OK"))
{
}
else
{
CustomMessageBox.Show("Set Command error");
}
}
}
else
{
if (controls[0].Text != values[2].Trim() && controls[0].Text != "")
{
string cmdanswer = doCommand(comPort, "RT" + values[0].Trim() + "=" + controls[0].Text + "\r");
if (cmdanswer.Contains("OK"))
{
}
else
{
CustomMessageBox.Show("Set Command error");
}
}
}
}
}
}
}
// write it
doCommand(comPort, "RT&W");
// return to normal mode
doCommand(comPort, "RTZ");
Sleep(100);
}
comPort.DiscardInBuffer();
{
//local
string answer = doCommand(comPort, "ATI5");
string[] items = answer.Split('\n');
foreach (string item in items)
{
if (item.StartsWith("S"))
{
string[] values = item.Split(':', '=');
if (values.Length == 3)
{
Control[] controls = this.Controls.Find(values[0].Trim(), true);
if (controls.Length > 0)
{
if (controls[0].GetType() == typeof(CheckBox))
{
string value = ((CheckBox)controls[0]).Checked ? "1" : "0";
if (value != values[2].Trim())
{
string cmdanswer = doCommand(comPort, "AT" + values[0].Trim() + "=" + value + "\r");
if (cmdanswer.Contains("OK"))
{
}
else
{
CustomMessageBox.Show("Set Command error");
}
}
}
else
{
if (controls[0].Text != values[2].Trim())
{
string cmdanswer = doCommand(comPort, "AT" + values[0].Trim() + "=" + controls[0].Text + "\r");
if (cmdanswer.Contains("OK"))
{
}
else
{
CustomMessageBox.Show("Set Command error");
}
}
}
}
}
}
}
// write it
doCommand(comPort, "AT&W");
// return to normal mode
doCommand(comPort, "ATZ");
}
lbl_status.Text = "Done";
}
else
{
// return to normal mode
doCommand(comPort, "ATZ");
lbl_status.Text = "Fail";
CustomMessageBox.Show("Failed to enter command mode");
}
comPort.Close();
}
public static IEnumerable<int> Range(int start,int step, int end)
{
List<int> list = new List<int>();
for (int a = start; a <= end; a += step)
{
list.Add(a);
}
return list;
}
private void BUT_getcurrent_Click(object sender, EventArgs e)
{
ArdupilotMega.Comms.ICommsSerial comPort = new SerialPort();
try
{
comPort.PortName = MainV2.comPort.BaseStream.PortName;
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
comPort.ReadTimeout = 4000;
comPort.Open();
}
catch { CustomMessageBox.Show("Invalid ComPort or in use"); return; }
lbl_status.Text = "Connecting";
if (doConnect(comPort))
{
// cleanup
doCommand(comPort, "AT&T");
comPort.DiscardInBuffer();
lbl_status.Text = "Doing Command ATI & RTI";
ATI.Text = doCommand(comPort, "ATI");
RTI.Text = doCommand(comPort, "RTI");
uploader.Uploader.Code freq = (uploader.Uploader.Code)Enum.Parse(typeof(uploader.Uploader.Code), doCommand(comPort, "ATI3"));
uploader.Uploader.Code board = (uploader.Uploader.Code)Enum.Parse(typeof(uploader.Uploader.Code), doCommand(comPort, "ATI2"));
ATI3.Text = freq.ToString();
// 8 and 9
if (freq == uploader.Uploader.Code.FREQ_915) {
S8.DataSource = Range(895000, 1000, 935000);
RS8.DataSource = Range(895000, 1000, 935000);
S9.DataSource = Range(895000, 1000, 935000);
RS9.DataSource = Range(895000, 1000, 935000);
}
else if (freq == uploader.Uploader.Code.FREQ_433)
{
S8.DataSource = Range(414000, 100, 454000);
RS8.DataSource = Range(414000, 100, 454000);
S9.DataSource = Range(414000, 100, 454000);
RS9.DataSource = Range(414000, 100, 454000);
}
else if (freq == uploader.Uploader.Code.FREQ_868)
{
S8.DataSource = Range(849000, 1000, 889000);
RS8.DataSource = Range(849000, 1000, 889000);
S9.DataSource = Range(849000, 1000, 889000);
RS9.DataSource = Range(849000, 1000, 889000);
}
if (board == uploader.Uploader.Code.DEVICE_ID_RFD900 || board == uploader.Uploader.Code.DEVICE_ID_RFD900A)
{
S4.DataSource = Range(1, 1, 30);
RS4.DataSource = Range(1, 1, 30);
}
RSSI.Text = doCommand(comPort, "ATI7").Trim();
lbl_status.Text = "Doing Command ATI5";
string answer = doCommand(comPort, "ATI5");
string[] items = answer.Split('\n');
foreach (string item in items)
{
if (item.StartsWith("S"))
{
string[] values = item.Split(':', '=');
if (values.Length == 3)
{
Control[] controls = this.Controls.Find(values[0].Trim(), true);
if (controls.Length > 0)
{
if (controls[0].GetType() == typeof(CheckBox))
{
((CheckBox)controls[0]).Checked = values[2].Trim() == "1";
}
else
{
controls[0].Text = values[2].Trim();
}
}
}
}
}
// remote
foreach (Control ctl in groupBox2.Controls)
{
if (ctl.Name.StartsWith("RS") && ctl.Name != "RSSI")
ctl.ResetText();
}
comPort.DiscardInBuffer();
lbl_status.Text = "Doing Command RTI5";
answer = doCommand(comPort, "RTI5");
items = answer.Split('\n');
foreach (string item in items)
{
if (item.StartsWith("S"))
{
string[] values = item.Split(':', '=');
if (values.Length == 3)
{
Control[] controls = this.Controls.Find("R" + values[0].Trim(), true);
if (controls.Length == 0)
continue;
if (controls[0].GetType() == typeof(CheckBox))
{
((CheckBox)controls[0]).Checked = values[2].Trim() == "1";
}
else if (controls[0].GetType() == typeof(TextBox))
{
((TextBox)controls[0]).Text = values[2].Trim();
}
else if (controls[0].GetType() == typeof(ComboBox))
{
((ComboBox)controls[0]).Text = values[2].Trim();
}
}
else
{
log.Info("Odd config line :" + item);
}
}
}
// off hook
doCommand(comPort, "ATO");
lbl_status.Text = "Done";
}
else
{
// off hook
doCommand(comPort, "ATO");
lbl_status.Text = "Fail";
CustomMessageBox.Show("Failed to enter command mode");
}
comPort.Close();
BUT_Syncoptions.Enabled = true;
BUT_savesettings.Enabled = true;
}
string Serial_ReadLine(ArdupilotMega.Comms.ICommsSerial comPort)
{
StringBuilder sb = new StringBuilder();
DateTime Deadline = DateTime.Now.AddMilliseconds(comPort.ReadTimeout);
while (DateTime.Now < Deadline)
{
if (comPort.BytesToRead > 0)
{
byte data = (byte)comPort.ReadByte();
sb.Append((char)data);
if (data == '\n')
break;
}
}
return sb.ToString();
}
public string doCommand(ArdupilotMega.Comms.ICommsSerial comPort, string cmd, int level = 0)
{
if (!comPort.IsOpen)
return "";
comPort.ReadTimeout = 1000;
// setup to known state
comPort.Write("\r\n");
// alow some time to gather thoughts
Sleep(100);
// ignore all existing data
comPort.DiscardInBuffer();
lbl_status.Text = "Doing Command " + cmd;
log.Info("Doing Command " + cmd);
// write command
comPort.Write(cmd + "\r\n");
// read echoed line or existing data
string temp;
try
{
temp = Serial_ReadLine(comPort);
}
catch { temp = comPort.ReadExisting(); }
log.Info("cmd " + cmd + " echo " + temp);
// delay for command
Sleep(500);
// get responce
string ans = "";
while (comPort.BytesToRead > 0)
{
try
{
ans = ans + Serial_ReadLine(comPort) + "\n";
}
catch { ans = ans + comPort.ReadExisting() + "\n"; }
Sleep(50);
if (ans.Length > 500)
{
break;
}
}
log.Info("responce " + level + " " + ans.Replace('\0', ' '));
// try again
if (ans == "" && level == 0)
return doCommand(comPort, cmd, 1);
return ans;
}
public bool doConnect(ArdupilotMega.Comms.ICommsSerial comPort)
{
try
{
// clear buffer
comPort.DiscardInBuffer();
// setup a known enviroment
comPort.Write("\r\n");
// wait
Sleep(1100);
// send config string
comPort.Write("+++");
// wait
Sleep(1100);
// check for config responce "OK"
log.Info("Connect btr " + comPort.BytesToRead + " baud " + comPort.BaudRate);
string conn = comPort.ReadExisting();
log.Info("Connect first responce " + conn.Replace('\0', ' ') + " " + conn.Length);
if (conn.Contains("OK"))
{
//return true;
}
else
{
// cleanup incase we are already in cmd mode
comPort.Write("\r\n");
}
doCommand(comPort, "AT&T");
string version = doCommand(comPort, "ATI");
log.Info("Connect Version: " + version.Trim() + "\n");
Regex regex = new Regex(@"SiK\s+(.*)\s+on\s+(.*)");
if (regex.IsMatch(version))
{
return true;
}
return false;
}
catch { return false; }
}
private void BUT_Syncoptions_Click(object sender, EventArgs e)
{
RS2.Text = S2.Text;
RS3.Text = S3.Text;
RS5.Checked = S5.Checked;
RS8.Text = S8.Text;
RS9.Text = S9.Text;
RS10.Text = S10.Text;
}
private void CHK_advanced_CheckedChanged(object sender, EventArgs e)
{
SPLIT_local.Panel2Collapsed = !CHK_advanced.Checked;
SPLIT_remote.Panel2Collapsed = !CHK_advanced.Checked;
}
private void linkLabel1_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e)
{
CustomMessageBox.Show(@"The 3DR Radios have 2 status LEDs, one red and one green.
green LED blinking - searching for another radio
green LED solid - link is established with another radio
red LED flashing - transmitting data
red LED solid - in firmware update mode");
}
private void BUT_resettodefault_Click(object sender, EventArgs e)
{
ArdupilotMega.Comms.ICommsSerial comPort = new SerialPort();
try
{
comPort.PortName = MainV2.comPort.BaseStream.PortName;
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
comPort.ReadTimeout = 4000;
comPort.Open();
}
catch { CustomMessageBox.Show("Invalid ComPort or in use"); return; }
lbl_status.Text = "Connecting";
if (doConnect(comPort))
{
// cleanup
doCommand(comPort, "AT&T");
comPort.DiscardInBuffer();
lbl_status.Text = "Doing Command ATI & AT&F";
doCommand(comPort, "AT&F");
doCommand(comPort, "AT&W");
lbl_status.Text = "Reset";
doCommand(comPort, "ATZ");
comPort.Close();
BUT_getcurrent_Click(sender, e);
}
else
{
// off hook
doCommand(comPort, "ATO");
lbl_status.Text = "Fail";
CustomMessageBox.Show("Failed to enter command mode");
}
if (comPort.IsOpen)
comPort.Close();
}
}
}