forked from ArduPilot/MissionPlanner
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Program.cs
345 lines (267 loc) · 12.2 KB
/
Program.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
using System;
using System.Collections.Generic;
using System.Windows.Forms;
using System.Net;
using System.IO;
using System.Text;
using System.Threading;
using log4net;
using log4net.Config;
using System.Diagnostics;
using System.Linq;
using MissionPlanner.Utilities;
namespace ArdupilotMega
{
static class Program
{
private static readonly ILog log = LogManager.GetLogger("Program");
public static Splash Splash;
/// <summary>
/// The main entry point for the application.
/// </summary>
[STAThread]
static void Main()
{
Console.WriteLine("If your error is about Microsoft.DirectX.DirectInput, please install the latest directx redist from here http://www.microsoft.com/en-us/download/details.aspx?id=35 \n\n");
Application.EnableVisualStyles();
XmlConfigurator.Configure();
log.Info("******************* Logging Configured *******************");
Application.SetCompatibleTextRenderingDefault(false);
Application.ThreadException += Application_ThreadException;
AppDomain.CurrentDomain.UnhandledException += new UnhandledExceptionEventHandler(CurrentDomain_UnhandledException);
// fix ssl on mono
ServicePointManager.ServerCertificateValidationCallback =
new System.Net.Security.RemoteCertificateValidationCallback((sender, certificate, chain, policyErrors) => { return true; });
CustomMessageBox.ApplyTheme += ArdupilotMega.Utilities.ThemeManager.ApplyThemeTo;
ArdupilotMega.Controls.MainSwitcher.ApplyTheme += ArdupilotMega.Utilities.ThemeManager.ApplyThemeTo;
MissionPlanner.Controls.InputBox.ApplyTheme += ArdupilotMega.Utilities.ThemeManager.ApplyThemeTo;
MissionPlanner.Comms.CommsBase.Settings += CommsBase_Settings;
//return;
// MissionPlanner.Utilities.CleanDrivers.Clean();
//Application.Idle += Application_Idle;
//MagCalib.ProcessLog();
//MessageBox.Show("NOTE: This version may break advanced mission scripting");
//Common.linearRegression();
//Console.WriteLine(srtm.getAltitude(-35.115676879882812, 117.94178754638671,20));
// Console.ReadLine();
// return;
/*
Arduino.ArduinoSTKv2 comport = new Arduino.ArduinoSTKv2();
comport.PortName = "com8";
comport.BaudRate = 115200;
comport.Open();
Arduino.Chip.Populate();
if (comport.connectAP())
{
Arduino.Chip chip = comport.getChipType();
Console.WriteLine(chip);
}
Console.ReadLine();
return;
*/
/*
Comms.SerialPort sp = new Comms.SerialPort();
sp.PortName = "com8";
sp.BaudRate = 115200;
CurrentState cs = new CurrentState();
MAVLink mav = new MAVLink();
mav.BaseStream = sp;
mav.Open();
HIL.XPlane xp = new HIL.XPlane();
xp.SetupSockets(49005, 49000, "127.0.0.1");
HIL.Hil.sitl_fdm data = new HIL.Hil.sitl_fdm();
while (true)
{
while (mav.BaseStream.BytesToRead > 0)
mav.readPacket();
// update all stats
cs.UpdateCurrentSettings(null);
xp.GetFromSim(ref data);
xp.GetFromAP(); // no function
xp.SendToAP(data);
xp.SendToSim();
MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
rc.chan3_raw = 1500;
mav.sendPacket(rc);
} */
/*
MAVLink mav = new MAVLink();
mav.BaseStream = new Comms.CommsFile()
{
PortName = @"C:\Users\hog\AppData\Roaming\Skype\My Skype Received Files\2013-06-12 15-11-00.tlog"
};
mav.Open(false);
while (mav.BaseStream.BytesToRead > 0)
{
byte[] packet = mav.readPacket();
mav.DebugPacket(packet, true);
}
*/
// return;
// OSDVideo vid = new OSDVideo();
// vid.ShowDialog();
// return;
// new Swarm.Control().ShowDialog();
// return;
// using (MainV3 main = new MainV3(1024, 768))
{
// main.Title = "Mission Planner";
// main.Run(30.0, 0.0);
}
// return;
// Utilities.RSA rsa = new Utilities.RSA();
// rsa.testit();
// return;
//Utilities.S3Uploader s3 = new Utilities.S3Uploader("");
//s3.UploadTlog(@"C:\Users\hog\Documents\apm logs\2012-10-27 15-05-54.tlog");
float t1 = 180;
float t2 = -180;
float t3 = -37.123456789f;
float t4 = 37.123456789f;
float t5 = 150.123456789f;
Console.WriteLine("7 digits {0} {1} {2} {3} {4}",t1,t2,t3,t4,t5);
if (File.Exists("simple.txt"))
{
Application.Run(new GCSViews.Simple());
return;
}
Splash = new ArdupilotMega.Splash();
Splash.Show();
Application.DoEvents();
try
{
Thread.CurrentThread.Name = "Base Thread";
Application.Run(new MainV2());
}
catch (Exception ex)
{
log.Fatal("Fatal app exception", ex);
Console.WriteLine(ex.ToString());
Console.WriteLine("\nPress any key to exit!");
Console.ReadLine();
}
}
static string CommsBase_Settings(string name, string value, bool set = false)
{
if (set) {
MainV2.config[name] = value;
return value;
}
if (MainV2.config.ContainsKey(name)) {
return MainV2.config[name].ToString();
}
return "";
}
static void CurrentDomain_UnhandledException(object sender, UnhandledExceptionEventArgs e)
{
handleException((Exception)e.ExceptionObject);
}
static DateTime lastidle = DateTime.Now;
static void Application_Idle(object sender, EventArgs e)
{
//System.Threading.Thread.Sleep(50);
Console.Write("Idle\n");
if (lastidle.AddMilliseconds(100) < DateTime.Now)
{
Application.DoEvents();
lastidle = DateTime.Now;
}
System.Threading.Thread.Sleep(1);
}
static void handleException(Exception ex)
{
MissionPlanner.Utilities.Tracking.AddException(ex);
log.Debug(ex.ToString());
if (ex.Message == "Requested registry access is not allowed.")
{
return;
}
if (ex.Message == "The port is closed.")
{
CustomMessageBox.Show("Serial connection has been lost");
return;
}
if (ex.Message == "A device attached to the system is not functioning.")
{
CustomMessageBox.Show("Serial connection has been lost");
return;
}
if (ex.GetType() == typeof(MissingMethodException))
{
CustomMessageBox.Show("Please Update - Some older library dlls are causing problems\n" + ex.Message);
return;
}
if (ex.GetType() == typeof(ObjectDisposedException) || ex.GetType() == typeof(InvalidOperationException)) // something is trying to update while the form, is closing.
{
return; // ignore
}
if (ex.GetType() == typeof(FileNotFoundException) || ex.GetType() == typeof(BadImageFormatException)) // i get alot of error from people who click the exe from inside a zip file.
{
CustomMessageBox.Show("You are missing some DLL's. Please extract the zip file somewhere. OR Use the update feature from the menu " + ex.ToString());
// return;
}
if (ex.StackTrace.Contains("System.IO.Ports.SerialStream.Dispose"))
{
return; // ignore
}
DialogResult dr = CustomMessageBox.Show("An error has occurred\n" + ex.ToString() + "\n\nReport this Error???", "Send Error", MessageBoxButtons.YesNo);
if (DialogResult.Yes == dr)
{
try
{
string data = "";
foreach (System.Collections.DictionaryEntry de in ex.Data)
data += String.Format("-> {0}: {1}", de.Key, de.Value);
// Create a request using a URL that can receive a post.
WebRequest request = WebRequest.Create("http://vps.oborne.me/mail.php");
request.Timeout = 10000; // 10 sec
// Set the Method property of the request to POST.
request.Method = "POST";
// Create POST data and convert it to a byte array.
string postData = "message=" + Environment.OSVersion.VersionString + " " + System.Reflection.Assembly.GetExecutingAssembly().GetName().Version.ToString()
+ " " + Application.ProductVersion
+ "\nException " + ex.ToString().Replace('&', ' ').Replace('=', ' ')
+ "\nStack: " + ex.StackTrace.ToString().Replace('&', ' ').Replace('=', ' ')
+ "\nTargetSite " + ex.TargetSite + " " + ex.TargetSite.DeclaringType
+ "\ndata " + data;
byte[] byteArray = Encoding.ASCII.GetBytes(postData);
// Set the ContentType property of the WebRequest.
request.ContentType = "application/x-www-form-urlencoded";
// Set the ContentLength property of the WebRequest.
request.ContentLength = byteArray.Length;
// Get the request stream.
Stream dataStream = request.GetRequestStream();
// Write the data to the request stream.
dataStream.Write(byteArray, 0, byteArray.Length);
// Close the Stream object.
dataStream.Close();
// Get the response.
WebResponse response = request.GetResponse();
// Display the status.
Console.WriteLine(((HttpWebResponse)response).StatusDescription);
// Get the stream containing content returned by the server.
dataStream = response.GetResponseStream();
// Open the stream using a StreamReader for easy access.
StreamReader reader = new StreamReader(dataStream);
// Read the content.
string responseFromServer = reader.ReadToEnd();
// Display the content.
Console.WriteLine(responseFromServer);
// Clean up the streams.
reader.Close();
dataStream.Close();
response.Close();
}
catch
{
CustomMessageBox.Show("Error sending Error report!! Youre most likerly are not on the internet");
}
}
}
static void Application_ThreadException(object sender, System.Threading.ThreadExceptionEventArgs e)
{
Exception ex = e.Exception;
handleException(ex);
}
}
}