Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | using System; |
2 | using System.Collections.Generic; |
||
3 | using System.Text; |
||
4 | using System.IO.Ports; |
||
5 | using System.Threading; |
||
6 | |||
7 | // Written by Michael Oborne |
||
8 | |||
9 | namespace ArdupilotMega |
||
10 | { |
||
11 | class ArduinoSTK : SerialPort |
||
12 | { |
||
13 | public delegate void ProgressEventHandler(int progress); |
||
14 | |||
15 | public event ProgressEventHandler Progress; |
||
16 | |||
17 | public new void Open() |
||
18 | { |
||
19 | // default dtr status is false |
||
20 | |||
21 | //from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup |
||
22 | base.Open(); |
||
23 | |||
24 | base.DtrEnable = false; |
||
25 | base.RtsEnable = false; |
||
26 | |||
27 | System.Threading.Thread.Sleep(50); |
||
28 | |||
29 | base.DtrEnable = true; |
||
30 | base.RtsEnable = true; |
||
31 | |||
32 | System.Threading.Thread.Sleep(50); |
||
33 | } |
||
34 | |||
35 | /// <summary> |
||
36 | /// Used to start initial connecting after serialport.open |
||
37 | /// </summary> |
||
38 | /// <returns>true = passed, false = failed</returns> |
||
39 | public bool connectAP() |
||
40 | { |
||
41 | if (!this.IsOpen) |
||
42 | { |
||
43 | return false; |
||
44 | } |
||
45 | int a = 0; |
||
46 | while (a < 50) |
||
47 | { |
||
48 | this.DiscardInBuffer(); |
||
49 | this.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2); |
||
50 | a++; |
||
51 | Thread.Sleep(50); |
||
52 | |||
53 | Console.WriteLine("btr {0}", this.BytesToRead); |
||
54 | if (this.BytesToRead >= 2) |
||
55 | { |
||
56 | byte b1 = (byte)this.ReadByte(); |
||
57 | byte b2 = (byte)this.ReadByte(); |
||
58 | if (b1 == 0x14 && b2 == 0x10) |
||
59 | { |
||
60 | return true; |
||
61 | } |
||
62 | } |
||
63 | } |
||
64 | |||
65 | return false; |
||
66 | } |
||
67 | |||
68 | /// <summary> |
||
69 | /// Used to keep alive the connection |
||
70 | /// </summary> |
||
71 | /// <returns>true = passed, false = lost connection</returns> |
||
72 | public bool keepalive() |
||
73 | { |
||
74 | return connectAP(); |
||
75 | } |
||
76 | /// <summary> |
||
77 | /// Syncs after a private command has been sent |
||
78 | /// </summary> |
||
79 | /// <returns>true = passed, false = failed</returns> |
||
80 | public bool sync() |
||
81 | { |
||
82 | if (!this.IsOpen) |
||
83 | { |
||
84 | return false; |
||
85 | } |
||
86 | this.ReadTimeout = 1000; |
||
87 | int f = 0; |
||
88 | while (this.BytesToRead < 1) |
||
89 | { |
||
90 | f++; |
||
91 | System.Threading.Thread.Sleep(1); |
||
92 | if (f > 1000) |
||
93 | return false; |
||
94 | } |
||
95 | int a = 0; |
||
96 | while (a < 10) |
||
97 | { |
||
98 | if (this.BytesToRead >= 2) |
||
99 | { |
||
100 | byte b1 = (byte)this.ReadByte(); |
||
101 | byte b2 = (byte)this.ReadByte(); |
||
102 | Console.WriteLine("bytes {0:X} {1:X}", b1, b2); |
||
103 | |||
104 | if (b1 == 0x14 && b2 == 0x10) |
||
105 | { |
||
106 | return true; |
||
107 | } |
||
108 | } |
||
109 | Console.WriteLine("btr {0}", this.BytesToRead); |
||
110 | Thread.Sleep(10); |
||
111 | a++; |
||
112 | } |
||
113 | return false; |
||
114 | } |
||
115 | /// <summary> |
||
116 | /// Downloads the eeprom with the given length - set Address first |
||
117 | /// </summary> |
||
118 | /// <param name="length">eeprom length</param> |
||
119 | /// <returns>downloaded data</returns> |
||
120 | public byte[] download(short length) |
||
121 | { |
||
122 | if (!this.IsOpen) |
||
123 | { |
||
124 | throw new Exception(); |
||
125 | } |
||
126 | byte[] data = new byte[length]; |
||
127 | |||
128 | byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'E', (byte)' ' }; |
||
129 | this.Write(command, 0, command.Length); |
||
130 | |||
131 | if (this.ReadByte() == 0x14) |
||
132 | { // 0x14 |
||
133 | |||
134 | int step = 0; |
||
135 | while (step < length) |
||
136 | { |
||
137 | byte chr = (byte)this.ReadByte(); |
||
138 | data[step] = chr; |
||
139 | step++; |
||
140 | } |
||
141 | |||
142 | if (this.ReadByte() != 0x10) // 0x10 |
||
143 | throw new Exception("Lost Sync 0x10"); |
||
144 | } |
||
145 | else |
||
146 | { |
||
147 | throw new Exception("Lost Sync 0x14"); |
||
148 | } |
||
149 | return data; |
||
150 | } |
||
151 | |||
152 | public byte[] downloadflash(short length) |
||
153 | { |
||
154 | if (!this.IsOpen) |
||
155 | { |
||
156 | throw new Exception("Port Not Open"); |
||
157 | } |
||
158 | byte[] data = new byte[length]; |
||
159 | |||
160 | this.ReadTimeout = 1000; |
||
161 | |||
162 | byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'F', (byte)' ' }; |
||
163 | this.Write(command, 0, command.Length); |
||
164 | |||
165 | if (this.ReadByte() == 0x14) |
||
166 | { // 0x14 |
||
167 | |||
168 | int read = length; |
||
169 | while (read > 0) |
||
170 | { |
||
171 | //Console.WriteLine("offset {0} read {1}", length - read, read); |
||
172 | read -= this.Read(data, length - read, read); |
||
173 | //System.Threading.Thread.Sleep(1); |
||
174 | } |
||
175 | |||
176 | if (this.ReadByte() != 0x10) // 0x10 |
||
177 | throw new Exception("Lost Sync 0x10"); |
||
178 | } |
||
179 | else |
||
180 | { |
||
181 | throw new Exception("Lost Sync 0x14"); |
||
182 | } |
||
183 | return data; |
||
184 | } |
||
185 | |||
186 | public bool uploadflash(byte[] data, int startfrom, int length, int startaddress) |
||
187 | { |
||
188 | if (!this.IsOpen) |
||
189 | { |
||
190 | return false; |
||
191 | } |
||
192 | int loops = (length / 0x100); |
||
193 | int totalleft = length; |
||
194 | int sending = 0; |
||
195 | |||
196 | for (int a = 0; a <= loops; a++) |
||
197 | { |
||
198 | if (totalleft > 0x100) |
||
199 | { |
||
200 | sending = 0x100; |
||
201 | } |
||
202 | else |
||
203 | { |
||
204 | sending = totalleft; |
||
205 | } |
||
206 | |||
207 | //startaddress = 256; |
||
208 | if (sending == 0) |
||
209 | return true; |
||
210 | |||
211 | setaddress(startaddress); |
||
212 | startaddress += sending; |
||
213 | |||
214 | byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'F' }; |
||
215 | this.Write(command, 0, command.Length); |
||
216 | Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending); |
||
217 | this.Write(data, startfrom + (length - totalleft), sending); |
||
218 | command = new byte[] { (byte)' ' }; |
||
219 | this.Write(command, 0, command.Length); |
||
220 | |||
221 | totalleft -= sending; |
||
222 | |||
223 | |||
224 | if (Progress != null) |
||
225 | Progress((int)(((float)startaddress / (float)length) * 100)); |
||
226 | |||
227 | if (!sync()) |
||
228 | { |
||
229 | Console.WriteLine("No Sync"); |
||
230 | return false; |
||
231 | } |
||
232 | } |
||
233 | return true; |
||
234 | } |
||
235 | |||
236 | /// <summary> |
||
237 | /// Sets the eeprom start read or write address |
||
238 | /// </summary> |
||
239 | /// <param name="address">address, must be eaven number</param> |
||
240 | /// <returns>true = passed, false = failed</returns> |
||
241 | public bool setaddress(int address) |
||
242 | { |
||
243 | if (!this.IsOpen) |
||
244 | { |
||
245 | return false; |
||
246 | } |
||
247 | |||
248 | if (address % 2 == 1) |
||
249 | { |
||
250 | throw new Exception("Address must be an even number"); |
||
251 | } |
||
252 | |||
253 | Console.WriteLine("Sending address " + ((ushort)(address / 2))); |
||
254 | |||
255 | address /= 2; |
||
256 | address = (ushort)address; |
||
257 | |||
258 | byte[] command = new byte[] { (byte)'U', (byte)(address & 0xff), (byte)(address >> 8), (byte)' ' }; |
||
259 | this.Write(command, 0, command.Length); |
||
260 | |||
261 | return sync(); |
||
262 | } |
||
263 | /// <summary> |
||
264 | /// Upload data at preset address |
||
265 | /// </summary> |
||
266 | /// <param name="data">array to read from</param> |
||
267 | /// <param name="startfrom">start array index</param> |
||
268 | /// <param name="length">length to send</param> |
||
269 | /// <param name="startaddress">sets eeprom start programing address</param> |
||
270 | /// <returns>true = passed, false = failed</returns> |
||
271 | public bool upload(byte[] data, short startfrom, short length, short startaddress) |
||
272 | { |
||
273 | if (!this.IsOpen) |
||
274 | { |
||
275 | return false; |
||
276 | } |
||
277 | int loops = (length / 0x100); |
||
278 | int totalleft = length; |
||
279 | int sending = 0; |
||
280 | |||
281 | for (int a = 0; a <= loops; a++) |
||
282 | { |
||
283 | if (totalleft > 0x100) |
||
284 | { |
||
285 | sending = 0x100; |
||
286 | } |
||
287 | else |
||
288 | { |
||
289 | sending = totalleft; |
||
290 | } |
||
291 | |||
292 | if (sending == 0) |
||
293 | return true; |
||
294 | |||
295 | setaddress(startaddress); |
||
296 | startaddress += (short)sending; |
||
297 | |||
298 | byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'E' }; |
||
299 | this.Write(command, 0, command.Length); |
||
300 | Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending); |
||
301 | this.Write(data, startfrom + (length - totalleft), sending); |
||
302 | command = new byte[] { (byte)' ' }; |
||
303 | this.Write(command, 0, command.Length); |
||
304 | |||
305 | totalleft -= sending; |
||
306 | |||
307 | if (!sync()) |
||
308 | { |
||
309 | Console.WriteLine("No Sync"); |
||
310 | return false; |
||
311 | } |
||
312 | } |
||
313 | return true; |
||
314 | } |
||
315 | |||
316 | public new bool Close() |
||
317 | { |
||
318 | try |
||
319 | { |
||
320 | |||
321 | byte[] command = new byte[] { (byte)'Q', (byte)' ' }; |
||
322 | this.Write(command, 0, command.Length); |
||
323 | } |
||
324 | catch { } |
||
325 | |||
326 | if (base.IsOpen) |
||
327 | base.Close(); |
||
328 | |||
329 | this.DtrEnable = false; |
||
330 | this.RtsEnable = false; |
||
331 | return true; |
||
332 | } |
||
333 | } |
||
334 | } |