forked from ArduPilot/MissionPlanner
-
Notifications
You must be signed in to change notification settings - Fork 0
/
FollowMe.cs
289 lines (246 loc) · 10.5 KB
/
FollowMe.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
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.Comms;
using System.Globalization;
using MissionPlanner.Controls;
using MissionPlanner.Utilities;
using System.IO;
namespace MissionPlanner
{
public partial class FollowMe : Form
{
System.Threading.Thread t12;
static bool threadrun = false;
static FollowMe Instance;
static internal SerialPort comPort = new SerialPort();
static internal PointLatLngAlt lastgotolocation = new PointLatLngAlt(0, 0, 0, "Goto last");
static internal PointLatLngAlt gotolocation = new PointLatLngAlt(0, 0, 0, "Goto");
static internal int intalt = 100;
static float updaterate = 0.5f;
public FollowMe()
{
Instance = this;
InitializeComponent();
CMB_serialport.DataSource = SerialPort.GetPortNames();
CMB_updaterate.SelectedItem = updaterate;
if (threadrun)
{
BUT_connect.Text = Strings.Stop;
CMB_baudrate.Text = comPort.BaudRate.ToString();
CMB_serialport.Text = comPort.PortName;
CMB_updaterate.Text = updaterate.ToString();
}
MissionPlanner.Utilities.Tracking.AddPage(
System.Reflection.MethodBase.GetCurrentMethod().DeclaringType.ToString(),
System.Reflection.MethodBase.GetCurrentMethod().Name);
}
private void BUT_connect_Click(object sender, EventArgs e)
{
if (comPort.IsOpen)
{
threadrun = false;
comPort.Close();
BUT_connect.Text = Strings.Connect;
}
else
{
try
{
comPort.PortName = CMB_serialport.Text;
}
catch
{
CustomMessageBox.Show(Strings.InvalidPortName, Strings.ERROR);
return;
}
try
{
comPort.BaudRate = int.Parse(CMB_baudrate.Text);
}
catch
{
CustomMessageBox.Show(Strings.InvalidBaudRate, Strings.ERROR);
return;
}
try
{
comPort.Open();
}
catch (Exception ex)
{
CustomMessageBox.Show(Strings.ErrorConnecting + "\n" + ex.ToString(), Strings.ERROR);
return;
}
string alt = "100";
if (MainV2.comPort.MAV.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
alt = (10*CurrentState.multiplierdist).ToString("0");
}
else
{
alt = (100*CurrentState.multiplierdist).ToString("0");
}
if (DialogResult.Cancel == InputBox.Show("Enter Alt", "Enter Alt (relative to home alt)", ref alt))
return;
intalt = (int) (100*CurrentState.multiplierdist);
if (!int.TryParse(alt, out intalt))
{
CustomMessageBox.Show(Strings.InvalidAlt, Strings.ERROR);
return;
}
intalt = (int) (intalt/CurrentState.multiplierdist);
t12 = new System.Threading.Thread(new System.Threading.ThreadStart(mainloop))
{
IsBackground = true,
Name = "followme Input"
};
t12.Start();
BUT_connect.Text = Strings.Stop;
}
}
void mainloop()
{
DateTime nextsend = DateTime.Now;
StreamWriter sw = new StreamWriter(File.OpenWrite("followmeraw.txt"));
threadrun = true;
while (threadrun)
{
try
{
string line = comPort.ReadLine();
sw.WriteLine(line);
//string line = string.Format("$GP{0},{1:HHmmss},{2},{3},{4},{5},{6},{7},{8},{9},{10},{11},{12},{13},", "GGA", DateTime.Now.ToUniversalTime(), Math.Abs(lat * 100), MainV2.comPort.MAV.cs.lat < 0 ? "S" : "N", Math.Abs(lng * 100), MainV2.comPort.MAV.cs.lng < 0 ? "W" : "E", MainV2.comPort.MAV.cs.gpsstatus, MainV2.comPort.MAV.cs.satcount, MainV2.comPort.MAV.cs.gpshdop, MainV2.comPort.MAV.cs.alt, "M", 0, "M", "");
if (line.StartsWith("$GPGGA") || line.StartsWith("$GNGGA")) //
{
string[] items = line.Trim().Split(',', '*');
if (items[15] != GetChecksum(line.Trim()))
{
Console.WriteLine("Bad Nmea line " + items[15] + " vs " + GetChecksum(line.Trim()));
continue;
}
if (items[6] == "0")
{
Console.WriteLine("No Fix");
continue;
}
gotolocation.Lat = double.Parse(items[2], CultureInfo.InvariantCulture)/100.0;
gotolocation.Lat = (int) gotolocation.Lat + ((gotolocation.Lat - (int) gotolocation.Lat)/0.60);
if (items[3] == "S")
gotolocation.Lat *= -1;
gotolocation.Lng = double.Parse(items[4], CultureInfo.InvariantCulture)/100.0;
gotolocation.Lng = (int) gotolocation.Lng + ((gotolocation.Lng - (int) gotolocation.Lng)/0.60);
if (items[5] == "W")
gotolocation.Lng *= -1;
gotolocation.Alt = intalt;
gotolocation.Tag = "Sats " + items[7] + " hdop " + items[8];
}
if (DateTime.Now > nextsend && gotolocation.Lat != 0 && gotolocation.Lng != 0 &&
gotolocation.Alt != 0) // 200 * 10 = 2 sec /// lastgotolocation != gotolocation &&
{
nextsend = DateTime.Now.AddMilliseconds(1000/updaterate);
Console.WriteLine("Sending follow wp " + DateTime.Now.ToString("h:MM:ss") + " " +
gotolocation.Lat + " " + gotolocation.Lng + " " + gotolocation.Alt);
lastgotolocation = new PointLatLngAlt(gotolocation);
Locationwp gotohere = new Locationwp();
gotohere.id = (ushort) MAVLink.MAV_CMD.WAYPOINT;
gotohere.alt = (float) (gotolocation.Alt);
gotohere.lat = (gotolocation.Lat);
gotohere.lng = (gotolocation.Lng);
try
{
updateLocationLabel(gotohere);
}
catch
{
}
if (MainV2.comPort.BaseStream.IsOpen && MainV2.comPort.giveComport == false)
{
try
{
MainV2.comPort.giveComport = true;
MainV2.comPort.setGuidedModeWP(gotohere, false);
MainV2.comPort.giveComport = false;
}
catch
{
MainV2.comPort.giveComport = false;
}
}
}
}
catch
{
System.Threading.Thread.Sleep((int) (1000/updaterate));
}
}
sw.Close();
}
private void updateLocationLabel(Locationwp plla)
{
if (!Instance.IsDisposed)
{
Instance.BeginInvoke(
(MethodInvoker)
delegate
{
Instance.LBL_location.Text = gotolocation.Lat + " " + gotolocation.Lng + " " +
gotolocation.Alt + " " + gotolocation.Tag;
}
);
}
}
private void SerialOutput_FormClosing(object sender, FormClosingEventArgs e)
{
}
// Calculates the checksum for a sentence
string GetChecksum(string sentence)
{
// Loop through all chars to get a checksum
int Checksum = 0;
foreach (char Character in sentence.ToCharArray())
{
switch (Character)
{
case '$':
// Ignore the dollar sign
break;
case '*':
// Stop processing before the asterisk
return Checksum.ToString("X2");
default:
// Is this the first value for the checksum?
if (Checksum == 0)
{
// Yes. Set the checksum to the value
Checksum = Convert.ToByte(Character);
}
else
{
// No. XOR the checksum with this character's value
Checksum = Checksum ^ Convert.ToByte(Character);
}
break;
}
}
// Return the checksum formatted as a two-character hexadecimal
return Checksum.ToString("X2");
}
private void CMB_updaterate_SelectedIndexChanged(object sender, EventArgs e)
{
try
{
updaterate = float.Parse(CMB_updaterate.Text.Replace("hz", ""));
}
catch
{
CustomMessageBox.Show(Strings.InvalidUpdateRate, Strings.ERROR);
}
}
}
}