forked from ArduPilot/MissionPlanner
-
Notifications
You must be signed in to change notification settings - Fork 0
/
MainV2.cs
2674 lines (2268 loc) · 109 KB
/
MainV2.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
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
using System;
using System.Collections.Generic;
using System.ComponentModel;
using System.Configuration;
using System.Drawing;
using System.Text;
using System.Windows.Forms;
using System.IO;
using System.Xml;
using System.Collections;
using System.Net;
using System.Text.RegularExpressions;
using System.Diagnostics;
using System.Runtime.InteropServices;
using System.Speech.Synthesis;
using System.Globalization;
using System.Threading;
using System.Net.Sockets;
using ArdupilotMega.Utilities;
using IronPython.Hosting;
using log4net;
using ArdupilotMega.Controls;
using System.Security.Cryptography;
using MissionPlanner.Comms;
using ArdupilotMega.Arduino;
using Transitions;
using System.Web.Script.Serialization;
using MissionPlanner.Controls;
namespace ArdupilotMega
{
public partial class MainV2 : Form
{
private static readonly ILog log =
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
private static class NativeMethods
{
// used to hide/show console window
[DllImport("user32.dll")]
public static extern int FindWindow(string szClass, string szTitle);
[DllImport("user32.dll")]
public static extern int ShowWindow(int Handle, int showState);
[DllImport("user32.dll", CharSet = CharSet.Auto, SetLastError = true)]
internal static extern IntPtr RegisterDeviceNotification
(IntPtr hRecipient,
IntPtr NotificationFilter,
Int32 Flags);
}
const int SW_SHOWNORMAL = 1;
const int SW_HIDE = 0;
ArdupilotMega.Controls.MainSwitcher MyView;
/// <summary>
/// Active Comport interface
/// </summary>
public static MAVLink comPort = new MAVLink();
/// <summary>
/// passive comports
/// </summary>
public static List<MAVLink> Comports = new List<MAVLink>();
/// <summary>
/// Comport name
/// </summary>
public static string comPortName = "";
/// <summary>
/// use to store all internal config
/// </summary>
public static Hashtable config = new Hashtable();
/// <summary>
/// mono detection
/// </summary>
public static bool MONO = false;
/// <summary>
/// speech engine enable
/// </summary>
public static bool speechEnable = false;
/// <summary>
/// spech engine static class
/// </summary>
public static Speech speechEngine = null;
/// <summary>
/// joystick static class
/// </summary>
public static Joystick joystick = null;
/// <summary>
/// track last joystick packet sent. used to control rate
/// </summary>
DateTime lastjoystick = DateTime.Now;
/// <summary>
/// hud background image grabber from a video stream - not realy that efficent. ie no hardware overlays etc.
/// </summary>
public static WebCamService.Capture cam = null;
/// <summary>
/// controls the main serial reader thread
/// </summary>
bool serialThread = false;
/// <summary>
/// track the last heartbeat sent
/// </summary>
private DateTime heatbeatSend = DateTime.Now;
/// <summary>
/// used to call anything as needed.
/// </summary>
public static MainV2 instance = null;
public static string LogDir {
get {
if (config["logdirectory"] == null)
return _logdir;
return config["logdirectory"].ToString();
}
set
{
_logdir = value;
config["logdirectory"] = value;
}
}
static string _logdir = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs";
public static MainSwitcher View;
/// <summary>
/// store the time we first connect
/// </summary>
DateTime connecttime = DateTime.Now;
DateTime nodatawarning = DateTime.Now;
/// <summary>
/// enum of firmwares
/// </summary>
public enum Firmwares
{
ArduPlane,
ArduCopter2,
ArduHeli,
ArduRover,
Ateryx
}
DateTime connectButtonUpdate = DateTime.Now;
/// <summary>
/// declared here if i want a "single" instance of the form
/// ie configuration gets reloaded on every click
/// </summary>
GCSViews.FlightData FlightData;
GCSViews.FlightPlanner FlightPlanner;
GCSViews.Simulation Simulation;
private Form connectionStatsForm;
private ConnectionStats _connectionStats;
/// <summary>
/// This 'Control' is the toolstrip control that holds the comport combo, baudrate combo etc
/// Otiginally seperate controls, each hosted in a toolstip sqaure, combined into this custom
/// control for layout reasons.
/// </summary>
static internal ConnectionControl _connectionControl;
public MainV2()
{
log.Info("Mainv2 ctor");
Form splash = Program.Splash;
string strVersion = System.Reflection.Assembly.GetExecutingAssembly().GetName().Version.ToString();
strVersion = "mav " + MAVLink.MAVLINK_WIRE_PROTOCOL_VERSION;
splash.Text = "Mission Planner " + Application.ProductVersion + " " + strVersion;
splash.Refresh();
Application.DoEvents();
instance = this;
InitializeComponent();
MenuFlightPlanner.Image = new Bitmap(MissionPlanner.Properties.Resources.flightplanner);
MyView = new MainSwitcher(this);
View = MyView;
_connectionControl = toolStripConnectionControl.ConnectionControl;
_connectionControl.CMB_baudrate.TextChanged += this.CMB_baudrate_TextChanged;
_connectionControl.CMB_baudrate.SelectedIndexChanged += this.CMB_baudrate_SelectedIndexChanged;
_connectionControl.CMB_serialport.SelectedIndexChanged += this.CMB_serialport_SelectedIndexChanged;
_connectionControl.CMB_serialport.Enter += this.CMB_serialport_Enter;
_connectionControl.CMB_serialport.Click += this.CMB_serialport_Click;
_connectionControl.TOOL_APMFirmware.SelectedIndexChanged += this.TOOL_APMFirmware_SelectedIndexChanged;
_connectionControl.ShowLinkStats += (sender, e) => ShowConnectionStatsForm();
srtm.datadirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "srtm";
var t = Type.GetType("Mono.Runtime");
MONO = (t != null);
speechEngine = new Speech();
// proxy loader - dll load now instead of on config form load
new Transition(new TransitionType_EaseInEaseOut(2000));
//MyRenderer.currentpressed = MenuFlightData;
//MainMenu.Renderer = new MyRenderer();
foreach (object obj in Enum.GetValues(typeof(Firmwares)))
{
_connectionControl.TOOL_APMFirmware.Items.Add(obj);
}
if (_connectionControl.TOOL_APMFirmware.Items.Count > 0)
_connectionControl.TOOL_APMFirmware.SelectedIndex = 0;
this.Text = splash.Text;
comPort.BaseStream.BaudRate = 115200;
// ** Old
// CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
// CMB_serialport.Items.Add("TCP");
// CMB_serialport.Items.Add("UDP");
// if (CMB_serialport.Items.Count > 0)
// {
// CMB_baudrate.SelectedIndex = 7;
// CMB_serialport.SelectedIndex = 0;
// }
// ** new
_connectionControl.CMB_serialport.Items.Add("AUTO");
_connectionControl.CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
_connectionControl.CMB_serialport.Items.Add("TCP");
_connectionControl.CMB_serialport.Items.Add("UDP");
if (_connectionControl.CMB_serialport.Items.Count > 0)
{
_connectionControl.CMB_baudrate.SelectedIndex = 7;
_connectionControl.CMB_serialport.SelectedIndex = 0;
}
// ** Done
splash.Refresh();
Application.DoEvents();
// set this before we reset it
MainV2.config["NUM_tracklength"] = "200";
// load config
xmlconfig(false);
if (config.ContainsKey("language") && !string.IsNullOrEmpty((string)config["language"]))
changelanguage(CultureInfoEx.GetCultureInfo((string)config["language"]));
if (!MONO) // windows only
{
if (MainV2.config["showconsole"] != null && MainV2.config["showconsole"].ToString() == "True")
{
}
else
{
int win = NativeMethods.FindWindow("ConsoleWindowClass", null);
NativeMethods.ShowWindow(win, SW_HIDE); // hide window
}
}
ChangeUnits();
if (config["theme"] != null)
{
ThemeManager.SetTheme((ThemeManager.Themes)Enum.Parse(typeof(ThemeManager.Themes), MainV2.config["theme"].ToString()));
if (ThemeManager.CurrentTheme == ThemeManager.Themes.Custom)
{
try
{
ThemeManager.BGColor = Color.FromArgb(int.Parse(MainV2.config["theme_bg"].ToString()));
ThemeManager.ControlBGColor = Color.FromArgb(int.Parse(MainV2.config["theme_ctlbg"].ToString()));
ThemeManager.TextColor = Color.FromArgb(int.Parse(MainV2.config["theme_text"].ToString()));
ThemeManager.ButBG = Color.FromArgb(int.Parse(MainV2.config["theme_butbg"].ToString()));
ThemeManager.ButBorder = Color.FromArgb(int.Parse(MainV2.config["theme_butbord"].ToString()));
}
catch { log.Error("Bad Custom theme - reset to standard"); ThemeManager.SetTheme(ThemeManager.Themes.BurntKermit); }
}
}
try
{
log.Info("Create FD");
FlightData = new GCSViews.FlightData();
log.Info("Create FP");
FlightPlanner = new GCSViews.FlightPlanner();
//Configuration = new GCSViews.ConfigurationView.Setup();
log.Info("Create SIM");
Simulation = new GCSViews.Simulation();
//Firmware = new GCSViews.Firmware();
//Terminal = new GCSViews.Terminal();
// preload
log.Info("Create Python");
Python.CreateEngine();
}
catch (ArgumentException e)
{
//http://www.microsoft.com/en-us/download/details.aspx?id=16083
//System.ArgumentException: Font 'Arial' does not support style 'Regular'.
log.Fatal(e);
CustomMessageBox.Show(e.ToString() + "\n\n Font Issues? Please install this http://www.microsoft.com/en-us/download/details.aspx?id=16083");
//splash.Close();
//this.Close();
Application.Exit();
}
catch (Exception e) { log.Fatal(e); CustomMessageBox.Show("A Major error has occured : " + e.ToString()); Application.Exit(); }
if (MainV2.config["CHK_GDIPlus"] != null)
GCSViews.FlightData.myhud.UseOpenGL = !bool.Parse(MainV2.config["CHK_GDIPlus"].ToString());
try
{
if (config["MainLocX"] != null && config["MainLocY"] != null)
{
this.StartPosition = FormStartPosition.Manual;
Point startpos = new Point(int.Parse(config["MainLocX"].ToString()), int.Parse(config["MainLocY"].ToString()));
this.Location = startpos;
}
if (config["MainMaximised"] != null)
{
this.WindowState = (FormWindowState)Enum.Parse(typeof(FormWindowState), config["MainMaximised"].ToString());
// dont allow minimised start state
if (this.WindowState == FormWindowState.Minimized)
{
this.WindowState = FormWindowState.Normal;
this.Location = new Point(100, 100);
}
}
if (config["MainHeight"] != null)
this.Height = int.Parse(config["MainHeight"].ToString());
if (config["MainWidth"] != null)
this.Width = int.Parse(config["MainWidth"].ToString());
if (config["CMB_rateattitude"] != null)
MainV2.comPort.MAV.cs.rateattitude = byte.Parse(config["CMB_rateattitude"].ToString());
if (config["CMB_rateposition"] != null)
MainV2.comPort.MAV.cs.rateposition = byte.Parse(config["CMB_rateposition"].ToString());
if (config["CMB_ratestatus"] != null)
MainV2.comPort.MAV.cs.ratestatus = byte.Parse(config["CMB_ratestatus"].ToString());
if (config["CMB_raterc"] != null)
MainV2.comPort.MAV.cs.raterc = byte.Parse(config["CMB_raterc"].ToString());
if (config["CMB_ratesensors"] != null)
MainV2.comPort.MAV.cs.ratesensors = byte.Parse(config["CMB_ratesensors"].ToString());
if (config["speechenable"] != null)
MainV2.speechEnable = bool.Parse(config["speechenable"].ToString());
//int fixme;
/*
MainV2.comPort.MAV.cs.rateattitude = 50;
MainV2.comPort.MAV.cs.rateposition = 50;
MainV2.comPort.MAV.cs.ratestatus = 50;
MainV2.comPort.MAV.cs.raterc = 50;
MainV2.comPort.MAV.cs.ratesensors = 50;
*/
try
{
if (config["TXT_homelat"] != null)
MainV2.comPort.MAV.cs.HomeLocation.Lat = double.Parse(config["TXT_homelat"].ToString());
if (config["TXT_homelng"] != null)
MainV2.comPort.MAV.cs.HomeLocation.Lng = double.Parse(config["TXT_homelng"].ToString());
if (config["TXT_homealt"] != null)
MainV2.comPort.MAV.cs.HomeLocation.Alt = double.Parse(config["TXT_homealt"].ToString());
}
catch { }
}
catch { }
if (MainV2.comPort.MAV.cs.rateattitude == 0) // initilised to 10, configured above from save
{
CustomMessageBox.Show("NOTE: your attitude rate is 0, the hud will not work\nChange in Configuration > Planner > Telemetry Rates");
}
// log dir
if (config["logdirectory"] != null)
MainV2.LogDir = config["logdirectory"].ToString();
//System.Threading.Thread.Sleep(2000);
// make sure new enough .net framework is installed
if (!MONO)
{
Microsoft.Win32.RegistryKey installed_versions = Microsoft.Win32.Registry.LocalMachine.OpenSubKey(@"SOFTWARE\Microsoft\NET Framework Setup\NDP");
string[] version_names = installed_versions.GetSubKeyNames();
//version names start with 'v', eg, 'v3.5' which needs to be trimmed off before conversion
double Framework = Convert.ToDouble(version_names[version_names.Length - 1].Remove(0, 1), CultureInfo.InvariantCulture);
int SP = Convert.ToInt32(installed_versions.OpenSubKey(version_names[version_names.Length - 1]).GetValue("SP", 0));
if (Framework < 3.5)
{
CustomMessageBox.Show("This program requires .NET Framework 3.5. You currently have " + Framework);
}
}
Application.DoEvents();
Comports.Add(comPort);
//int fixmenextrelease;
// if (MainV2.getConfig("fixparams") == "")
{
// Utilities.ParameterMetaDataParser.GetParameterInformation();
// MainV2.config["fixparams"] = 1;
}
splash.Close();
}
private void ResetConnectionStats()
{
// If the form has been closed, or never shown before, we need do nothing, as
// connection stats will be reset when shown
if (this.connectionStatsForm != null && connectionStatsForm.Visible)
{
// else the form is already showing. reset the stats
this.connectionStatsForm.Controls.Clear();
_connectionStats = new ConnectionStats(comPort);
this.connectionStatsForm.Controls.Add(_connectionStats);
ThemeManager.ApplyThemeTo(this.connectionStatsForm);
}
}
private void ShowConnectionStatsForm()
{
if (this.connectionStatsForm == null || this.connectionStatsForm.IsDisposed)
{
// If the form has been closed, or never shown before, we need all new stuff
this.connectionStatsForm = new Form
{
Width = 430,
Height = 180,
MaximizeBox = false,
MinimizeBox = false,
FormBorderStyle = FormBorderStyle.FixedDialog,
Text = "Link Stats"
};
// Change the connection stats control, so that when/if the connection stats form is showing,
// there will be something to see
this.connectionStatsForm.Controls.Clear();
_connectionStats = new ConnectionStats(comPort);
this.connectionStatsForm.Controls.Add(_connectionStats);
this.connectionStatsForm.Width = _connectionStats.Width;
}
this.connectionStatsForm.Show();
ThemeManager.ApplyThemeTo(this.connectionStatsForm);
}
/// <summary>
/// used to create planner screenshots - access by control-s
/// </summary>
internal void ScreenShot()
{
Rectangle bounds = Screen.GetBounds(Point.Empty);
using (Bitmap bitmap = new Bitmap(bounds.Width, bounds.Height))
{
using (Graphics g = Graphics.FromImage(bitmap))
{
g.CopyFromScreen(Point.Empty, Point.Empty, bounds.Size);
}
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);
}
}
private void CMB_serialport_Click(object sender, EventArgs e)
{
string oldport = _connectionControl.CMB_serialport.Text;
_connectionControl.CMB_serialport.Items.Clear();
_connectionControl.CMB_serialport.Items.Add("AUTO");
_connectionControl.CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
_connectionControl.CMB_serialport.Items.Add("TCP");
_connectionControl.CMB_serialport.Items.Add("UDP");
if (_connectionControl.CMB_serialport.Items.Contains(oldport))
_connectionControl.CMB_serialport.Text = oldport;
}
private void MenuFlightData_Click(object sender, EventArgs e)
{
MyView.ShowScreen("FlightData");
}
private void MenuFlightPlanner_Click(object sender, EventArgs e)
{
// refresh ap/ac specific items
FlightPlanner.updateCMDParams();
MyView.ShowScreen("FlightPlanner");
}
public void MenuConfiguration_Click(object sender, EventArgs e)
{
MyView.ShowScreen("HWConfig");
}
private void MenuSimulation_Click(object sender, EventArgs e)
{
MyView.ShowScreen("Simulation");
}
private void MenuFirmware_Click(object sender, EventArgs e)
{
MyView.ShowScreen("SWConfig");
}
private void MenuTerminal_Click(object sender, EventArgs e)
{
MyView.ShowScreen("Terminal");
}
private void MenuConnect_Click(object sender, EventArgs e)
{
comPort.giveComport = false;
// sanity check
if (comPort.BaseStream.IsOpen && MainV2.comPort.MAV.cs.groundspeed > 4)
{
if (DialogResult.No == CustomMessageBox.Show("Your model is still moving are you sure you want to disconnect?", "Disconnect", MessageBoxButtons.YesNo))
{
return;
}
}
// cleanup from any previous sessions
if (comPort.logfile != null)
comPort.logfile.Close();
if (comPort.rawlogfile != null)
comPort.rawlogfile.Close();
comPort.logfile = null;
comPort.rawlogfile = null;
// decide if this is a connect or disconnect
if (comPort.BaseStream.IsOpen)
{
try
{
if (speechEngine != null) // cancel all pending speech
speechEngine.SpeakAsyncCancelAll();
comPort.BaseStream.DtrEnable = false;
comPort.Close();
}
catch (Exception ex)
{
log.Error(ex);
}
// now that we have closed the connection, cancel the connection stats
// so that the 'time connected' etc does not grow, but the user can still
// look at the now frozen stats on the still open form
try
{
// if terminal is used, then closed using this button.... exception
((ConnectionStats)this.connectionStatsForm.Controls[0]).StopUpdates();
}
catch { }
// refresh config window if needed
if (MyView.current != null)
{
if (MyView.current.Name == "HWConfig")
MyView.ShowScreen("HWConfig");
if (MyView.current.Name == "SWConfig")
MyView.ShowScreen("SWConfig");
}
this.MenuConnect.Image = global::MissionPlanner.Properties.Resources.connect;
}
else
{
switch (_connectionControl.CMB_serialport.Text)
{
case "TCP":
comPort.BaseStream = new TcpSerial();
break;
case "UDP":
comPort.BaseStream = new UdpSerial();
break;
case "AUTO":
default:
comPort.BaseStream = new SerialPort();
break;
}
// Tell the connection UI that we are now connected.
_connectionControl.IsConnected(true);
// Here we want to reset the connection stats counter etc.
this.ResetConnectionStats();
MainV2.comPort.MAV.cs.timeInAir = 0;
//cleanup any log being played
comPort.logreadmode = false;
if (comPort.logplaybackfile != null)
comPort.logplaybackfile.Close();
comPort.logplaybackfile = null;
try
{
// do autoscan
if (_connectionControl.CMB_serialport.Text == "AUTO")
{
Comms.CommsSerialScan.Scan(false);
DateTime deadline = DateTime.Now.AddSeconds(50);
while (Comms.CommsSerialScan.foundport == false)
{
System.Threading.Thread.Sleep(100);
if (DateTime.Now > deadline) {
CustomMessageBox.Show("Timeout waiting for autoscan/no mavlink device connected");
_connectionControl.IsConnected(false);
return;
}
}
_connectionControl.CMB_serialport.Text = Comms.CommsSerialScan.portinterface.PortName;
_connectionControl.CMB_baudrate.Text = Comms.CommsSerialScan.portinterface.BaudRate.ToString();
}
// set port, then options
comPort.BaseStream.PortName = _connectionControl.CMB_serialport.Text;
try
{
comPort.BaseStream.BaudRate = int.Parse(_connectionControl.CMB_baudrate.Text);
}
catch (Exception exp) { log.Error(exp); }
// false here
comPort.BaseStream.DtrEnable = false;
comPort.BaseStream.RtsEnable = false;
// prevent serialreader from doing anything
comPort.giveComport = true;
// reset on connect logic.
if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true)
comPort.BaseStream.toggleDTR();
comPort.giveComport = false;
// setup to record new logs
try
{
Directory.CreateDirectory(MainV2.LogDir);
comPort.logfile = new BinaryWriter(File.Open(MainV2.LogDir + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".tlog", FileMode.CreateNew, FileAccess.ReadWrite, FileShare.None));
comPort.rawlogfile = new BinaryWriter(File.Open(MainV2.LogDir + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + ".rlog", FileMode.CreateNew, FileAccess.ReadWrite, FileShare.None));
}
catch (Exception exp2) { log.Error(exp2); CustomMessageBox.Show("Failed to create log - wont log this session"); } // soft fail
// reset connect time - for timeout functions
connecttime = DateTime.Now;
// do the connect
comPort.Open(true);
// detect firmware we are conected to.
if (comPort.MAV.param["SYSID_SW_TYPE"] != null)
{
if (float.Parse(comPort.MAV.param["SYSID_SW_TYPE"].ToString()) == 10)
{
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduCopter2);
}
else if (float.Parse(comPort.MAV.param["SYSID_SW_TYPE"].ToString()) == 7)
{
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.Items.IndexOf(Firmwares.Ateryx);
}
else if (float.Parse(comPort.MAV.param["SYSID_SW_TYPE"].ToString()) == 20)
{
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduRover);
}
else if (float.Parse(comPort.MAV.param["SYSID_SW_TYPE"].ToString()) == 0)
{
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.Items.IndexOf(Firmwares.ArduPlane);
}
}
// save the baudrate for this port
config[_connectionControl.CMB_serialport.Text + "_BAUD"] = _connectionControl.CMB_baudrate.Text;
// refresh config window if needed
if (MyView.current != null)
{
if (MyView.current.Name == "HWConfig")
MyView.ShowScreen("HWConfig");
if (MyView.current.Name == "SWConfig")
MyView.ShowScreen("SWConfig");
}
// load wps on connect option.
if (config["loadwpsonconnect"] != null && bool.Parse(config["loadwpsonconnect"].ToString()) == true)
{
MenuFlightPlanner_Click(null, null);
FlightPlanner.BUT_read_Click(null, null);
}
// set connected icon
this.MenuConnect.Image = global::MissionPlanner.Properties.Resources.disconnect;
}
catch (Exception ex)
{
log.Warn(ex);
try
{
_connectionControl.IsConnected(false);
UpdateConnectIcon();
comPort.Close();
}
catch { }
CustomMessageBox.Show(@"Can not establish a connection\n\n" + ex.Message);
return;
}
}
}
private void CMB_serialport_SelectedIndexChanged(object sender, EventArgs e)
{
comPortName = _connectionControl.CMB_serialport.Text;
if (comPortName == "UDP" || comPortName == "TCP" || comPortName == "AUTO")
{
_connectionControl.CMB_baudrate.Enabled = false;
if (comPortName == "TCP")
MainV2.comPort.BaseStream = new TcpSerial();
if (comPortName == "UDP")
MainV2.comPort.BaseStream = new UdpSerial();
if (comPortName == "AUTO")
{
MainV2.comPort.BaseStream = new SerialPort();
return;
}
}
else
{
_connectionControl.CMB_baudrate.Enabled = true;
MainV2.comPort.BaseStream = new SerialPort();
}
try
{
comPort.BaseStream.PortName = _connectionControl.CMB_serialport.Text;
MainV2.comPort.BaseStream.BaudRate = int.Parse(_connectionControl.CMB_baudrate.Text);
// check for saved baud rate and restore
if (config[_connectionControl.CMB_serialport.Text + "_BAUD"] != null)
{
_connectionControl.CMB_baudrate.Text = config[_connectionControl.CMB_serialport.Text + "_BAUD"].ToString();
}
}
catch { }
}
private void MainV2_FormClosed(object sender, FormClosedEventArgs e)
{
// shutdown threads
GCSViews.FlightData.threadrun = 0;
// shutdown local thread
serialThread = false;
SerialThreadrunner.WaitOne();
try
{
if (comPort.BaseStream.IsOpen)
comPort.Close();
}
catch { } // i get alot of these errors, the port is still open, but not valid - user has unpluged usb
try
{
FlightData.Dispose();
}
catch { }
try
{
FlightPlanner.Dispose();
}
catch { }
try
{
Simulation.Dispose();
}
catch { }
// save config
xmlconfig(true);
}
private void xmlconfig(bool write)
{
if (write || !File.Exists(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"config.xml"))
{
try
{
XmlTextWriter xmlwriter = new XmlTextWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"config.xml", Encoding.ASCII);
xmlwriter.Formatting = Formatting.Indented;
xmlwriter.WriteStartDocument();
xmlwriter.WriteStartElement("Config");
xmlwriter.WriteElementString("comport", comPortName);
xmlwriter.WriteElementString("baudrate", _connectionControl.CMB_baudrate.Text);
xmlwriter.WriteElementString("APMFirmware", MainV2.comPort.MAV.cs.firmware.ToString());
foreach (string key in config.Keys)
{
try
{
if (key == "" || key.Contains("/")) // "/dev/blah"
continue;
xmlwriter.WriteElementString(key, config[key].ToString());
}
catch { }
}
xmlwriter.WriteEndElement();
xmlwriter.WriteEndDocument();
xmlwriter.Close();
}
catch (Exception ex) { CustomMessageBox.Show(ex.ToString()); }
}
else
{
try
{
using (XmlTextReader xmlreader = new XmlTextReader(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"config.xml"))
{
while (xmlreader.Read())
{
xmlreader.MoveToElement();
try
{
switch (xmlreader.Name)
{
case "comport":
string temp = xmlreader.ReadString();
_connectionControl.CMB_serialport.SelectedIndex = _connectionControl.CMB_serialport.FindString(temp);
if (_connectionControl.CMB_serialport.SelectedIndex == -1)
{
_connectionControl.CMB_serialport.Text = temp; // allows ports that dont exist - yet
}
comPort.BaseStream.PortName = temp;
comPortName = temp;
break;
case "baudrate":
string temp2 = xmlreader.ReadString();
_connectionControl.CMB_baudrate.SelectedIndex = _connectionControl.CMB_baudrate.FindString(temp2);
if (_connectionControl.CMB_baudrate.SelectedIndex == -1)
{
_connectionControl.CMB_baudrate.Text = temp2;
//CMB_baudrate.SelectedIndex = CMB_baudrate.FindString("57600"); ; // must exist
}
//bau = int.Parse(CMB_baudrate.Text);
break;
case "APMFirmware":
string temp3 = xmlreader.ReadString();
_connectionControl.TOOL_APMFirmware.SelectedIndex = _connectionControl.TOOL_APMFirmware.FindStringExact(temp3);
if (_connectionControl.TOOL_APMFirmware.SelectedIndex == -1)
_connectionControl.TOOL_APMFirmware.SelectedIndex = 0;
MainV2.comPort.MAV.cs.firmware = (MainV2.Firmwares)Enum.Parse(typeof(MainV2.Firmwares), _connectionControl.TOOL_APMFirmware.Text);
break;
case "Config":
break;
case "xml":
break;
default:
if (xmlreader.Name == "") // line feeds
break;
config[xmlreader.Name] = xmlreader.ReadString();
break;
}
}
// silent fail on bad entry
catch (Exception ee)
{
log.Error(ee);
}
}
}
}
catch (Exception ex)
{
log.Error("Bad Config File", ex);
}
}
}
private void CMB_baudrate_SelectedIndexChanged(object sender, EventArgs e)
{
try
{
comPort.BaseStream.BaudRate = int.Parse(_connectionControl.CMB_baudrate.Text);
}
catch
{
}
}
/// <summary>
/// thread used to send joystick packets to the MAV
/// </summary>
private void joysticksend()
{
float rate = 50;
int count = 0;
DateTime lastratechange = DateTime.Now;
while (true)
{
try
{
if (MONO)
{
log.Error("Mono: closing joystick thread");
break;
}
if (!MONO)
{
//joystick stuff
if (joystick != null && joystick.enabled)
{
MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
rc.target_component = comPort.MAV.compid;
rc.target_system = comPort.MAV.sysid;
if (joystick.getJoystickAxis(1) != Joystick.joystickaxis.None)
rc.chan1_raw = MainV2.comPort.MAV.cs.rcoverridech1;//(ushort)(((int)state.Rz / 65.535) + 1000);
if (joystick.getJoystickAxis(2) != Joystick.joystickaxis.None)
rc.chan2_raw = MainV2.comPort.MAV.cs.rcoverridech2;//(ushort)(((int)state.Y / 65.535) + 1000);
if (joystick.getJoystickAxis(3) != Joystick.joystickaxis.None)
rc.chan3_raw = MainV2.comPort.MAV.cs.rcoverridech3;//(ushort)(1000 - ((int)slider[0] / 65.535 ) + 1000);
if (joystick.getJoystickAxis(4) != Joystick.joystickaxis.None)
rc.chan4_raw = MainV2.comPort.MAV.cs.rcoverridech4;//(ushort)(((int)state.X / 65.535) + 1000);
if (joystick.getJoystickAxis(5) != Joystick.joystickaxis.None)
rc.chan5_raw = MainV2.comPort.MAV.cs.rcoverridech5;
if (joystick.getJoystickAxis(6) != Joystick.joystickaxis.None)
rc.chan6_raw = MainV2.comPort.MAV.cs.rcoverridech6;
if (joystick.getJoystickAxis(7) != Joystick.joystickaxis.None)
rc.chan7_raw = MainV2.comPort.MAV.cs.rcoverridech7;
if (joystick.getJoystickAxis(8) != Joystick.joystickaxis.None)
rc.chan8_raw = MainV2.comPort.MAV.cs.rcoverridech8;
if (lastjoystick.AddMilliseconds(rate) < DateTime.Now)
{
/*
if (MainV2.comPort.MAV.cs.rssi > 0 && MainV2.comPort.MAV.cs.remrssi > 0)
{
if (lastratechange.Second != DateTime.Now.Second)
{
if (MainV2.comPort.MAV.cs.txbuffer > 90)
{
if (rate < 20)
rate = 21;
rate--;