Rev 2135 | Details | Compare with Previous | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
2108 | - | 1 | #include <avr/io.h> |
2 | #include <avr/interrupt.h> |
||
3 | #include <avr/wdt.h> |
||
4 | #include <avr/pgmspace.h> |
||
5 | #include <stdarg.h> |
||
6 | #include <string.h> |
||
7 | |||
8 | #include "eeprom.h" |
||
9 | #include "timer0.h" |
||
10 | #include "uart0.h" |
||
11 | #include "rc.h" |
||
12 | #include "externalControl.h" |
||
13 | #include "output.h" |
||
14 | #include "attitude.h" |
||
15 | #include "commands.h" |
||
2132 | - | 16 | #include "main.h" |
2108 | - | 17 | |
18 | #define FC_ADDRESS 1 |
||
19 | #define NC_ADDRESS 2 |
||
20 | #define MK3MAG_ADDRESS 3 |
||
21 | |||
22 | #define FALSE 0 |
||
23 | #define TRUE 1 |
||
24 | |||
25 | int8_t displayBuff[DISPLAYBUFFSIZE]; |
||
26 | uint8_t dispPtr = 0; |
||
27 | |||
28 | uint8_t requestedDebugLabel = 255; |
||
29 | uint8_t request_verInfo = FALSE; |
||
30 | uint8_t request_externalControl = FALSE; |
||
31 | uint8_t request_debugData = FALSE; |
||
32 | uint8_t request_data3D = FALSE; |
||
33 | uint8_t request_PPMChannels = FALSE; |
||
34 | uint8_t request_servoTest = FALSE; |
||
35 | uint8_t request_variables = FALSE; |
||
36 | uint8_t request_OSD = FALSE; |
||
37 | |||
38 | /* |
||
39 | #define request_verInfo (1<<0) |
||
40 | #define request_externalControl (1<<1) |
||
41 | #define request_display (1<<3) |
||
42 | #define request_display1 (1<<4) |
||
43 | #define request_debugData (1<<5) |
||
44 | #define request_data3D (1<<6) |
||
45 | #define request_PPMChannels (1<<7) |
||
46 | #define request_motorTest (1<<8) |
||
47 | #define request_variables (1<<9) |
||
48 | #define request_OSD (1<<10) |
||
49 | */ |
||
50 | |||
51 | //uint16_t request = 0; |
||
52 | |||
53 | volatile uint8_t txd_buffer[TXD_BUFFER_LEN]; |
||
54 | volatile uint8_t rxd_buffer_locked = FALSE; |
||
55 | volatile uint8_t rxd_buffer[RXD_BUFFER_LEN]; |
||
56 | volatile uint8_t txd_complete = TRUE; |
||
57 | volatile uint8_t receivedBytes = 0; |
||
58 | volatile uint8_t *pRxData = 0; |
||
59 | volatile uint8_t rxDataLen = 0; |
||
60 | |||
61 | uint8_t servoTestActive = 0; |
||
62 | uint8_t servoTest[16] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; |
||
63 | uint8_t confirmFrame; |
||
64 | |||
65 | typedef struct { |
||
66 | int16_t heading; |
||
67 | }__attribute__((packed)) Heading_t; |
||
68 | |||
69 | Data3D_t data3D; |
||
70 | |||
71 | uint16_t debugData_timer; |
||
72 | uint16_t data3D_timer; |
||
73 | uint16_t OSD_timer; |
||
74 | uint16_t debugData_interval = 0; // in 1ms |
||
75 | uint16_t data3D_interval = 0; // in 1ms |
||
76 | uint16_t OSD_interval = 0; |
||
77 | |||
78 | #ifdef USE_DIRECT_GPS |
||
79 | int16_t toMk3MagTimer; |
||
80 | #endif |
||
81 | |||
82 | // keep lables in flash to save 512 bytes of sram space |
||
83 | const prog_uint8_t ANALOG_LABEL[32][16] = { |
||
84 | //1234567890123456 |
||
85 | "Gyro P ", //0 |
||
86 | "Gyro R ", |
||
87 | "Gyro Y ", |
||
88 | "Attitude P ", |
||
89 | "Attitude R ", |
||
90 | "Attitude Y ", //5 |
||
91 | "Target P ", |
||
92 | "Target R ", |
||
93 | "Target Y ", |
||
2141 | - | 94 | "GyroD P ", |
95 | "GyroD R ", //10 |
||
96 | "GyroD Y ", |
||
2108 | - | 97 | "Term P ", |
98 | "Term R ", |
||
2135 | - | 99 | "Term Y ", |
100 | "Throttle ", //15 |
||
2108 | - | 101 | "Flight mode ", |
2109 | - | 102 | "Ultralow thr. ", |
103 | "Var0 ", |
||
104 | "Var1 ", |
||
2108 | - | 105 | "RC P ", //20 |
106 | "RC R ", |
||
2135 | - | 107 | "RC Y ", |
2108 | - | 108 | "RC T ", |
109 | "Servo P ", |
||
110 | "Servo R ", //25 |
||
111 | "Servo T ", |
||
112 | "Servo Y ", |
||
2109 | - | 113 | "I2C cycles ", |
114 | "I2C restarts ", |
||
2135 | - | 115 | "case0 ", //30 |
116 | "case1 " |
||
2108 | - | 117 | }; |
118 | |||
119 | /****************************************************************/ |
||
120 | /* Initialization of the USART0 */ |
||
121 | /****************************************************************/ |
||
122 | void usart0_init(void) { |
||
123 | uint8_t sreg = SREG; |
||
2133 | - | 124 | uint16_t ubrr = (uint16_t) ((uint32_t) F_CPU / (8 * USART0_BAUD) - 1); |
2108 | - | 125 | |
126 | // disable all interrupts before configuration |
||
127 | cli(); |
||
128 | |||
129 | // disable RX-Interrupt |
||
130 | UCSR0B &= ~(1 << RXCIE0); |
||
131 | // disable TX-Interrupt |
||
132 | UCSR0B &= ~(1 << TXCIE0); |
||
133 | |||
134 | // set direction of RXD0 and TXD0 pins |
||
135 | // set RXD0 (PD0) as an input pin |
||
136 | PORTD |= (1 << PORTD0); |
||
137 | DDRD &= ~(1 << DDD0); |
||
138 | // set TXD0 (PD1) as an output pin |
||
139 | PORTD |= (1 << PORTD1); |
||
140 | DDRD |= (1 << DDD1); |
||
141 | |||
142 | // USART0 Baud Rate Register |
||
143 | // set clock divider |
||
144 | UBRR0H = (uint8_t) (ubrr >> 8); |
||
145 | UBRR0L = (uint8_t) ubrr; |
||
146 | |||
147 | // USART0 Control and Status Register A, B, C |
||
148 | |||
149 | // enable double speed operation in |
||
150 | UCSR0A |= (1 << U2X0); |
||
151 | // enable receiver and transmitter in |
||
152 | UCSR0B = (1 << TXEN0) | (1 << RXEN0); |
||
153 | // set asynchronous mode |
||
154 | UCSR0C &= ~(1 << UMSEL01); |
||
155 | UCSR0C &= ~(1 << UMSEL00); |
||
156 | // no parity |
||
157 | UCSR0C &= ~(1 << UPM01); |
||
158 | UCSR0C &= ~(1 << UPM00); |
||
159 | // 1 stop bit |
||
160 | UCSR0C &= ~(1 << USBS0); |
||
161 | // 8-bit |
||
162 | UCSR0B &= ~(1 << UCSZ02); |
||
163 | UCSR0C |= (1 << UCSZ01); |
||
164 | UCSR0C |= (1 << UCSZ00); |
||
165 | |||
166 | // flush receive buffer |
||
167 | while (UCSR0A & (1 << RXC0)) |
||
168 | UDR0; |
||
169 | |||
170 | // enable interrupts at the end |
||
171 | // enable RX-Interrupt |
||
172 | UCSR0B |= (1 << RXCIE0); |
||
173 | // enable TX-Interrupt |
||
174 | UCSR0B |= (1 << TXCIE0); |
||
175 | |||
176 | // initialize the debug timer |
||
177 | debugData_timer = setDelay(debugData_interval); |
||
178 | |||
179 | // unlock rxd_buffer |
||
180 | rxd_buffer_locked = FALSE; |
||
181 | pRxData = 0; |
||
182 | rxDataLen = 0; |
||
183 | |||
184 | // no bytes to send |
||
185 | txd_complete = TRUE; |
||
186 | |||
187 | versionInfo.SWMajor = VERSION_MAJOR; |
||
188 | versionInfo.SWMinor = VERSION_MINOR; |
||
189 | versionInfo.SWPatch = VERSION_PATCH; |
||
190 | versionInfo.protoMajor = VERSION_SERIAL_MAJOR; |
||
191 | versionInfo.protoMinor = VERSION_SERIAL_MINOR; |
||
192 | |||
193 | // restore global interrupt flags |
||
194 | SREG = sreg; |
||
195 | } |
||
196 | |||
197 | /****************************************************************/ |
||
198 | /* USART0 transmitter ISR */ |
||
199 | /****************************************************************/ |
||
200 | ISR(USART_TX_vect) { |
||
201 | static uint16_t ptr_txd_buffer = 0; |
||
202 | uint8_t tmp_tx; |
||
203 | if (!txd_complete) { // transmission not completed |
||
204 | ptr_txd_buffer++; // die [0] wurde schon gesendet |
||
205 | tmp_tx = txd_buffer[ptr_txd_buffer]; |
||
206 | // if terminating character or end of txd buffer was reached |
||
207 | if ((tmp_tx == '\r') || (ptr_txd_buffer == TXD_BUFFER_LEN)) { |
||
208 | ptr_txd_buffer = 0; // reset txd pointer |
||
209 | txd_complete = 1; // stop transmission |
||
210 | } |
||
211 | UDR0 = tmp_tx; // send current byte will trigger this ISR again |
||
212 | } |
||
213 | // transmission completed |
||
214 | else |
||
215 | ptr_txd_buffer = 0; |
||
216 | } |
||
217 | |||
218 | /****************************************************************/ |
||
219 | /* USART0 receiver ISR */ |
||
220 | /****************************************************************/ |
||
221 | ISR(USART_RX_vect) { |
||
222 | static uint16_t checksum; |
||
223 | static uint8_t ptr_rxd_buffer = 0; |
||
224 | uint8_t checksum1, checksum2; |
||
225 | uint8_t c; |
||
226 | |||
227 | c = UDR0; // catch the received byte |
||
228 | |||
229 | if (rxd_buffer_locked) |
||
230 | return; // if rxd buffer is locked immediately return |
||
231 | |||
232 | // the rxd buffer is unlocked |
||
233 | if ((ptr_rxd_buffer == 0) && (c == '#')) { // if rxd buffer is empty and syncronisation character is received |
||
234 | rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer |
||
235 | checksum = c; // init checksum |
||
236 | } |
||
237 | else if (ptr_rxd_buffer < RXD_BUFFER_LEN) { // collect incomming bytes |
||
238 | if (c != '\r') { // no termination character |
||
239 | rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer |
||
240 | checksum += c; // update checksum |
||
241 | } else { // termination character was received |
||
242 | // the last 2 bytes are no subject for checksum calculation |
||
243 | // they are the checksum itself |
||
244 | checksum -= rxd_buffer[ptr_rxd_buffer - 2]; |
||
245 | checksum -= rxd_buffer[ptr_rxd_buffer - 1]; |
||
246 | // calculate checksum from transmitted data |
||
247 | checksum %= 4096; |
||
248 | checksum1 = '=' + checksum / 64; |
||
249 | checksum2 = '=' + checksum % 64; |
||
250 | // compare checksum to transmitted checksum bytes |
||
251 | if ((checksum1 == rxd_buffer[ptr_rxd_buffer - 2]) && (checksum2 |
||
252 | == rxd_buffer[ptr_rxd_buffer - 1])) { |
||
253 | // checksum valid |
||
254 | rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character |
||
255 | receivedBytes = ptr_rxd_buffer + 1;// store number of received bytes |
||
256 | rxd_buffer_locked = TRUE; // lock the rxd buffer |
||
257 | // if 2nd byte is an 'R' enable watchdog that will result in an reset |
||
258 | if (rxd_buffer[2] == 'R') { |
||
2132 | - | 259 | reset(); |
260 | } |
||
2108 | - | 261 | } else { // checksum invalid |
262 | rxd_buffer_locked = FALSE; // unlock rxd buffer |
||
263 | } |
||
264 | ptr_rxd_buffer = 0; // reset rxd buffer pointer |
||
265 | } |
||
266 | } else { // rxd buffer overrun |
||
267 | ptr_rxd_buffer = 0; // reset rxd buffer |
||
268 | rxd_buffer_locked = FALSE; // unlock rxd buffer |
||
269 | } |
||
270 | } |
||
271 | |||
272 | // -------------------------------------------------------------------------- |
||
273 | void addChecksum(uint16_t datalen) { |
||
274 | uint16_t tmpchecksum = 0, i; |
||
275 | for (i = 0; i < datalen; i++) { |
||
276 | tmpchecksum += txd_buffer[i]; |
||
277 | } |
||
278 | tmpchecksum %= 4096; |
||
279 | txd_buffer[i++] = '=' + (tmpchecksum >> 6); |
||
280 | txd_buffer[i++] = '=' + (tmpchecksum & 0x3F); |
||
281 | txd_buffer[i++] = '\r'; |
||
282 | txd_complete = FALSE; |
||
283 | UDR0 = txd_buffer[0]; // initiates the transmittion (continued in the TXD ISR) |
||
284 | } |
||
285 | |||
286 | // -------------------------------------------------------------------------- |
||
287 | // application example: |
||
288 | // sendOutData('A', FC_ADDRESS, 2, (uint8_t *)&request_DebugLabel, sizeof(request_DebugLabel), label, 16); |
||
289 | /* |
||
290 | void sendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) { // uint8_t *pdata, uint8_t len, ... |
||
291 | va_list ap; |
||
292 | uint16_t txd_bufferIndex = 0; |
||
293 | uint8_t *currentBuffer; |
||
294 | uint8_t currentBufferIndex; |
||
295 | uint16_t lengthOfCurrentBuffer; |
||
296 | uint8_t shift = 0; |
||
297 | |||
298 | txd_buffer[txd_bufferIndex++] = '#'; // Start character |
||
299 | txd_buffer[txd_bufferIndex++] = 'a' + addr; // Address (a=0; b=1,...) |
||
300 | txd_buffer[txd_bufferIndex++] = cmd; // Command |
||
301 | |||
302 | va_start(ap, numofbuffers); |
||
303 | |||
304 | while(numofbuffers) { |
||
305 | currentBuffer = va_arg(ap, uint8_t*); |
||
306 | lengthOfCurrentBuffer = va_arg(ap, int); |
||
307 | currentBufferIndex = 0; |
||
308 | // Encode data: 3 bytes of data are encoded into 4 bytes, |
||
309 | // where the 2 most significant bits are both 0. |
||
310 | while(currentBufferIndex != lengthOfCurrentBuffer) { |
||
311 | if (!shift) txd_buffer[txd_bufferIndex] = 0; |
||
312 | txd_buffer[txd_bufferIndex] |= currentBuffer[currentBufferIndex] >> (shift + 2); |
||
313 | txd_buffer[++txd_bufferIndex] = (currentBuffer[currentBufferIndex] << (4 - shift)) & 0b00111111; |
||
314 | shift += 2; |
||
315 | if (shift == 6) { shift=0; txd_bufferIndex++; } |
||
316 | currentBufferIndex++; |
||
317 | } |
||
318 | } |
||
319 | // If the number of data bytes was not divisible by 3, stuff |
||
320 | // with 0 pseudodata until length is again divisible by 3. |
||
321 | if (shift == 2) { |
||
322 | // We need to stuff with zero bytes at the end. |
||
323 | txd_buffer[txd_bufferIndex] &= 0b00110000; |
||
324 | txd_buffer[++txd_bufferIndex] = 0; |
||
325 | shift = 4; |
||
326 | } |
||
327 | if (shift == 4) { |
||
328 | // We need to stuff with zero bytes at the end. |
||
329 | txd_buffer[txd_bufferIndex++] &= 0b00111100; |
||
330 | txd_buffer[txd_bufferIndex] = 0; |
||
331 | } |
||
332 | va_end(ap); |
||
333 | Addchecksum(pt); // add checksum after data block and initates the transmission |
||
334 | } |
||
335 | */ |
||
336 | |||
337 | void sendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) { // uint8_t *pdata, uint8_t len, ... |
||
338 | va_list ap; |
||
339 | uint16_t pt = 0; |
||
340 | uint8_t a, b, c; |
||
341 | uint8_t ptr = 0; |
||
342 | |||
343 | uint8_t *pdata = 0; |
||
344 | int len = 0; |
||
345 | |||
346 | txd_buffer[pt++] = '#'; // Start character |
||
347 | txd_buffer[pt++] = 'a' + addr; // Address (a=0; b=1,...) |
||
348 | txd_buffer[pt++] = cmd; // Command |
||
349 | |||
350 | va_start(ap, numofbuffers); |
||
351 | |||
352 | if (numofbuffers) { |
||
353 | pdata = va_arg(ap, uint8_t*); |
||
354 | len = va_arg(ap, int); |
||
355 | ptr = 0; |
||
356 | numofbuffers--; |
||
357 | } |
||
358 | |||
359 | while (len) { |
||
360 | if (len) { |
||
361 | a = pdata[ptr++]; |
||
362 | len--; |
||
363 | if ((!len) && numofbuffers) { |
||
364 | pdata = va_arg(ap, uint8_t*); |
||
365 | len = va_arg(ap, int); |
||
366 | ptr = 0; |
||
367 | numofbuffers--; |
||
368 | } |
||
369 | } else |
||
370 | a = 0; |
||
371 | if (len) { |
||
372 | b = pdata[ptr++]; |
||
373 | len--; |
||
374 | if ((!len) && numofbuffers) { |
||
375 | pdata = va_arg(ap, uint8_t*); |
||
376 | len = va_arg(ap, int); |
||
377 | ptr = 0; |
||
378 | numofbuffers--; |
||
379 | } |
||
380 | } else |
||
381 | b = 0; |
||
382 | if (len) { |
||
383 | c = pdata[ptr++]; |
||
384 | len--; |
||
385 | if ((!len) && numofbuffers) { |
||
386 | pdata = va_arg(ap, uint8_t*); |
||
387 | len = va_arg(ap, int); |
||
388 | ptr = 0; |
||
389 | numofbuffers--; |
||
390 | } |
||
391 | } else |
||
392 | c = 0; |
||
393 | txd_buffer[pt++] = '=' + (a >> 2); |
||
394 | txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4)); |
||
395 | txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6)); |
||
396 | txd_buffer[pt++] = '=' + (c & 0x3f); |
||
397 | } |
||
398 | va_end(ap); |
||
399 | addChecksum(pt); // add checksum after data block and initates the transmission |
||
400 | } |
||
401 | |||
402 | // -------------------------------------------------------------------------- |
||
403 | void decode64(void) { |
||
404 | uint8_t a, b, c, d; |
||
405 | uint8_t x, y, z; |
||
406 | uint8_t ptrIn = 3; |
||
407 | uint8_t ptrOut = 3; |
||
408 | uint8_t len = receivedBytes - 6; |
||
409 | |||
410 | while (len) { |
||
411 | a = rxd_buffer[ptrIn++] - '='; |
||
412 | b = rxd_buffer[ptrIn++] - '='; |
||
413 | c = rxd_buffer[ptrIn++] - '='; |
||
414 | d = rxd_buffer[ptrIn++] - '='; |
||
415 | //if(ptrIn > ReceivedBytes - 3) break; |
||
416 | |||
417 | x = (a << 2) | (b >> 4); |
||
418 | y = ((b & 0x0f) << 4) | (c >> 2); |
||
419 | z = ((c & 0x03) << 6) | d; |
||
420 | |||
421 | if (len--) |
||
422 | rxd_buffer[ptrOut++] = x; |
||
423 | else |
||
424 | break; |
||
425 | if (len--) |
||
426 | rxd_buffer[ptrOut++] = y; |
||
427 | else |
||
428 | break; |
||
429 | if (len--) |
||
430 | rxd_buffer[ptrOut++] = z; |
||
431 | else |
||
432 | break; |
||
433 | } |
||
434 | pRxData = &rxd_buffer[3]; |
||
435 | rxDataLen = ptrOut - 3; |
||
436 | } |
||
437 | |||
438 | // -------------------------------------------------------------------------- |
||
439 | void usart0_processRxData(void) { |
||
440 | // We control the servoTestActive var from here: Count it down. |
||
441 | if (servoTestActive) |
||
442 | servoTestActive--; |
||
443 | // if data in the rxd buffer are not locked immediately return |
||
444 | if (!rxd_buffer_locked) |
||
445 | return; |
||
446 | uint8_t tempchar[3]; |
||
447 | decode64(); // decode data block in rxd_buffer |
||
448 | |||
449 | switch (rxd_buffer[1] - 'a') { |
||
450 | |||
451 | case FC_ADDRESS: |
||
452 | switch (rxd_buffer[2]) { |
||
453 | #ifdef USE_DIRECT_GPS |
||
454 | case 'K':// compass value |
||
455 | // What is the point of this - the compass will overwrite this soon? |
||
456 | magneticHeading = ((Heading_t *)pRxData)->heading; |
||
457 | // compassOffCourse = ((540 + compassHeading - compassCourse) % 360) - 180; |
||
458 | break; |
||
459 | #endif |
||
460 | case 't': // motor test |
||
461 | if (rxDataLen > 20) { |
||
462 | memcpy(&servoTest[0], (uint8_t*) pRxData, sizeof(servoTest)); |
||
463 | } else { |
||
464 | memcpy(&servoTest[0], (uint8_t*) pRxData, 4); |
||
465 | } |
||
466 | servoTestActive = 255; |
||
467 | externalControlActive = 255; |
||
468 | break; |
||
469 | |||
470 | case 'p': // get PPM channels |
||
471 | request_PPMChannels = TRUE; |
||
472 | break; |
||
473 | |||
474 | case 'i':// Read IMU configuration |
||
475 | tempchar[0] = IMUCONFIG_REVISION; |
||
476 | tempchar[1] = sizeof(IMUConfig); |
||
477 | while (!txd_complete) |
||
478 | ; // wait for previous frame to be sent |
||
479 | sendOutData('I', FC_ADDRESS, 2, &tempchar, 2, (uint8_t *) &IMUConfig, sizeof(IMUConfig)); |
||
480 | break; |
||
481 | |||
482 | case 'j':// Save IMU configuration |
||
483 | if (!isFlying) // save settings only if motors are off |
||
484 | { |
||
485 | if ((pRxData[0] == IMUCONFIG_REVISION) && (pRxData[1] == sizeof(IMUConfig))) { |
||
486 | memcpy(&IMUConfig, (uint8_t*) &pRxData[2], sizeof(IMUConfig)); |
||
487 | IMUConfig_writeToEEprom(); |
||
488 | tempchar[0] = 1; //indicate ok data |
||
489 | } else { |
||
490 | tempchar[0] = 0; //indicate bad data |
||
491 | } |
||
492 | while (!txd_complete) |
||
493 | ; // wait for previous frame to be sent |
||
494 | sendOutData('J', FC_ADDRESS, 1, &tempchar, 1); |
||
495 | } |
||
496 | break; |
||
497 | |||
498 | case 'q':// request settings |
||
499 | if (pRxData[0] == 0xFF) { |
||
500 | pRxData[0] = getParamByte(PID_ACTIVE_SET); |
||
501 | } |
||
502 | // limit settings range |
||
503 | if (pRxData[0] < 1) |
||
504 | pRxData[0] = 1; // limit to 1 |
||
505 | else if (pRxData[0] > 5) |
||
506 | pRxData[0] = 5; // limit to 5 |
||
507 | // load requested parameter set |
||
508 | |||
509 | paramSet_readFromEEProm(pRxData[0]); |
||
510 | |||
511 | tempchar[0] = pRxData[0]; |
||
512 | tempchar[1] = EEPARAM_REVISION; |
||
513 | tempchar[2] = sizeof(staticParams); |
||
514 | while (!txd_complete) |
||
515 | ; // wait for previous frame to be sent |
||
516 | sendOutData('Q', FC_ADDRESS, 2, &tempchar, 3, (uint8_t *) &staticParams, sizeof(staticParams)); |
||
517 | break; |
||
518 | |||
519 | case 's': // save settings |
||
520 | if (!isFlying) // save settings only if motors are off |
||
521 | { |
||
522 | if ((pRxData[1] == EEPARAM_REVISION) && (pRxData[2] == sizeof(staticParams))) // check for setting to be in range and version of settings |
||
523 | { |
||
524 | memcpy(&staticParams, (uint8_t*) &pRxData[3], sizeof(staticParams)); |
||
525 | paramSet_writeToEEProm(1); |
||
526 | configuration_paramSetDidChange(); |
||
527 | tempchar[0] = 1; |
||
528 | beepNumber(tempchar[0]); |
||
529 | } else { |
||
530 | tempchar[0] = 0; //indicate bad data |
||
531 | } |
||
532 | while (!txd_complete) |
||
533 | ; // wait for previous frame to be sent |
||
534 | sendOutData('S', FC_ADDRESS, 1, &tempchar, 1); |
||
535 | } |
||
536 | break; |
||
537 | |||
538 | default: |
||
539 | //unsupported command received |
||
540 | break; |
||
541 | } // case FC_ADDRESS: |
||
542 | |||
543 | default: // any Slave Address |
||
544 | switch (rxd_buffer[2]) { |
||
545 | case 'a':// request for labels of the analog debug outputs |
||
546 | requestedDebugLabel = pRxData[0]; |
||
547 | if (requestedDebugLabel > 31) |
||
548 | requestedDebugLabel = 31; |
||
549 | break; |
||
550 | |||
551 | case 'b': // submit extern control |
||
552 | memcpy(&externalControl, (uint8_t*) pRxData, sizeof(externalControl)); |
||
553 | confirmFrame = externalControl.frame; |
||
554 | externalControlActive = 255; |
||
555 | break; |
||
556 | |||
557 | case 'o':// request for OSD data (FC style) |
||
558 | OSD_interval = (uint16_t) pRxData[0] * 10; |
||
559 | if (OSD_interval > 0) |
||
560 | request_OSD = TRUE; |
||
561 | break; |
||
562 | |||
563 | case 'v': // request for version and board release |
||
564 | request_verInfo = TRUE; |
||
565 | break; |
||
566 | |||
567 | case 'x': |
||
568 | request_variables = TRUE; |
||
569 | break; |
||
570 | |||
571 | case 'g':// get external control data |
||
572 | request_externalControl = TRUE; |
||
573 | break; |
||
574 | |||
575 | case 'd': // request for the debug data |
||
576 | debugData_interval = (uint16_t) pRxData[0] * 10; |
||
577 | if (debugData_interval > 0) |
||
578 | request_debugData = TRUE; |
||
579 | break; |
||
580 | |||
581 | case 'c': // request for the 3D data |
||
582 | data3D_interval = (uint16_t) pRxData[0] * 10; |
||
583 | if (data3D_interval > 0) |
||
584 | request_data3D = TRUE; |
||
585 | break; |
||
586 | |||
587 | default: |
||
588 | //unsupported command received |
||
589 | break; |
||
590 | } |
||
591 | break; // default: |
||
592 | } |
||
593 | // unlock the rxd buffer after processing |
||
594 | pRxData = 0; |
||
595 | rxDataLen = 0; |
||
596 | rxd_buffer_locked = FALSE; |
||
597 | } |
||
598 | |||
599 | /************************************************************************/ |
||
600 | /* Routine f�r die Serielle Ausgabe */ |
||
601 | /************************************************************************/ |
||
602 | int16_t uart_putchar(int8_t c) { |
||
603 | if (c == '\n') |
||
604 | uart_putchar('\r'); |
||
605 | // wait until previous character was send |
||
606 | loop_until_bit_is_set(UCSR0A, UDRE0); |
||
607 | // send character |
||
608 | UDR0 = c; |
||
609 | return (0); |
||
610 | } |
||
611 | |||
612 | //--------------------------------------------------------------------------------------------- |
||
613 | void usart0_transmitTxData(void) { |
||
614 | if (!txd_complete) |
||
615 | return; |
||
616 | |||
617 | if (request_verInfo && txd_complete) { |
||
618 | sendOutData('V', FC_ADDRESS, 1, (uint8_t *) &versionInfo, sizeof(versionInfo)); |
||
619 | request_verInfo = FALSE; |
||
620 | } |
||
621 | |||
622 | if (requestedDebugLabel != 0xFF && txd_complete) { // Texte f�r die Analogdaten |
||
623 | uint8_t label[16]; // local sram buffer |
||
624 | memcpy_P(label, ANALOG_LABEL[requestedDebugLabel], 16); // read lable from flash to sram buffer |
||
625 | sendOutData('A', FC_ADDRESS, 2, (uint8_t *) &requestedDebugLabel, |
||
626 | sizeof(requestedDebugLabel), label, 16); |
||
627 | requestedDebugLabel = 0xFF; |
||
628 | } |
||
629 | |||
630 | if (confirmFrame && txd_complete) { // Datensatz ohne checksum best�tigen |
||
631 | sendOutData('B', FC_ADDRESS, 1, (uint8_t*) &confirmFrame, sizeof(confirmFrame)); |
||
632 | confirmFrame = 0; |
||
633 | } |
||
634 | |||
635 | if (((debugData_interval && checkDelay(debugData_timer)) || request_debugData) |
||
636 | && txd_complete) { |
||
637 | sendOutData('D', FC_ADDRESS, 1, (uint8_t *) &debugOut, sizeof(debugOut)); |
||
638 | debugData_timer = setDelay(debugData_interval); |
||
639 | request_debugData = FALSE; |
||
640 | } |
||
641 | |||
642 | if (((data3D_interval && checkDelay(data3D_timer)) || request_data3D) && txd_complete) { |
||
643 | sendOutData('C', FC_ADDRESS, 1, (uint8_t *) &data3D, sizeof(data3D)); |
||
644 | data3D.anglePitch = (int16_t) (attitude[PITCH] / (GYRO_DEG_FACTOR/10)); // convert to multiple of 0.1 deg |
||
645 | data3D.angleRoll = (int16_t) (attitude[ROLL] / (GYRO_DEG_FACTOR/10)); // convert to multiple of 0.1 deg |
||
646 | data3D.heading = (int16_t) (attitude[YAW] / (GYRO_DEG_FACTOR/10)); // convert to multiple of 0.1 deg |
||
647 | data3D_timer = setDelay(data3D_interval); |
||
648 | request_data3D = FALSE; |
||
649 | } |
||
650 | |||
651 | if (request_externalControl && txd_complete) { |
||
652 | sendOutData('G', FC_ADDRESS, 1, (uint8_t *) &externalControl, |
||
653 | sizeof(externalControl)); |
||
654 | request_externalControl = FALSE; |
||
655 | } |
||
656 | |||
657 | |||
658 | if (request_servoTest && txd_complete) { |
||
659 | sendOutData('T', FC_ADDRESS, 0); |
||
660 | request_servoTest = FALSE; |
||
661 | } |
||
662 | |||
663 | if (request_PPMChannels && txd_complete) { |
||
664 | sendOutData('P', FC_ADDRESS, 1, (uint8_t *) &PPM_in, sizeof(PPM_in)); |
||
665 | request_PPMChannels = FALSE; |
||
666 | } |
||
667 | |||
668 | if (request_variables && txd_complete) { |
||
669 | sendOutData('X', FC_ADDRESS, 1, (uint8_t *) &variables, sizeof(variables)); |
||
670 | request_variables = FALSE; |
||
671 | } |
||
672 | |||
673 | if (((OSD_interval && checkDelay(OSD_timer)) || request_OSD) && txd_complete) { |
||
674 | int32_t height = 0; |
||
675 | data3D.anglePitch = (int16_t) (attitude[PITCH] / (GYRO_DEG_FACTOR/10)); // convert to multiple of 0.1 deg |
||
676 | data3D.angleRoll = (int16_t) (attitude[ROLL] / (GYRO_DEG_FACTOR/10)); // convert to multiple of 0.1 deg |
||
677 | // TODO: To 0..359 interval. |
||
678 | data3D.heading = (int16_t) (attitude[YAW] / (GYRO_DEG_FACTOR/10)); // convert to multiple of 0.1 deg |
||
679 | sendOutData('O', FC_ADDRESS, 3, (uint8_t*)&data3D, sizeof(data3D), (uint8_t*)&height, sizeof(height), (uint8_t*)UBat, sizeof(UBat)); |
||
680 | OSD_timer = setDelay(OSD_interval); |
||
681 | request_OSD = FALSE; |
||
682 | } |
||
683 | } |