Rev 1646 | Rev 1796 | Go to most recent revision | Details | Compare with Previous | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1612 | dongfang | 1 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
2 | // + Copyright (c) 04.2007 Holger Buss |
||
1623 | - | 3 | // + Nur für den privaten Gebrauch |
1612 | dongfang | 4 | // + www.MikroKopter.com |
5 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
1623 | - | 6 | // + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation), |
7 | // + dass eine Nutzung (auch auszugsweise) nur für den privaten und nicht-kommerziellen Gebrauch zulässig ist. |
||
1612 | dongfang | 8 | // + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt |
9 | // + bzgl. der Nutzungsbedingungen aufzunehmen. |
||
1623 | - | 10 | // + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen, |
1612 | dongfang | 11 | // + Verkauf von Luftbildaufnahmen, usw. |
12 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
1623 | - | 13 | // + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht, |
14 | // + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen |
||
1612 | dongfang | 15 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
16 | // + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts |
||
1623 | - | 17 | // + auf anderen Webseiten oder Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de" |
18 | // + eindeutig als Ursprung verlinkt und genannt werden |
||
1612 | dongfang | 19 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
1623 | - | 20 | // + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion |
1612 | dongfang | 21 | // + Benutzung auf eigene Gefahr |
1623 | - | 22 | // + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden |
1612 | dongfang | 23 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
24 | // + Die Portierung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur |
||
1623 | - | 25 | // + mit unserer Zustimmung zulässig |
1612 | dongfang | 26 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
27 | // + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen |
||
28 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
29 | // + Redistributions of source code (with or without modifications) must retain the above copyright notice, |
||
30 | // + this list of conditions and the following disclaimer. |
||
31 | // + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived |
||
32 | // + from this software without specific prior written permission. |
||
33 | // + * The use of this project (hardware, software, binary files, sources and documentation) is only permittet |
||
34 | // + for non-commercial use (directly or indirectly) |
||
35 | // + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted |
||
36 | // + with our written permission |
||
37 | // + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be |
||
38 | // + clearly linked as origin |
||
39 | // + * porting to systems other than hardware from www.mikrokopter.de is not allowed |
||
40 | // + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" |
||
41 | // + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE |
||
42 | // + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
||
43 | // + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE |
||
44 | // + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR |
||
45 | // + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF |
||
46 | // + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS |
||
1623 | - | 47 | // + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN |
48 | // + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) |
||
1612 | dongfang | 49 | // + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
50 | // + POSSIBILITY OF SUCH DAMAGE. |
||
51 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
1623 | - | 52 | |
1612 | dongfang | 53 | #include <avr/io.h> |
54 | #include <avr/interrupt.h> |
||
55 | #include <avr/wdt.h> |
||
56 | #include <avr/pgmspace.h> |
||
57 | #include <stdarg.h> |
||
58 | #include <string.h> |
||
59 | |||
60 | #include "eeprom.h" |
||
61 | #include "menu.h" |
||
62 | #include "timer0.h" |
||
63 | #include "uart0.h" |
||
64 | #include "attitude.h" |
||
65 | #include "rc.h" |
||
66 | #include "externalControl.h" |
||
1775 | - | 67 | #include "output.h" |
1612 | dongfang | 68 | |
69 | #if defined (USE_MK3MAG) |
||
70 | #include "ubx.h" |
||
71 | #endif |
||
72 | #ifdef USE_MK3MAG |
||
73 | #include "mk3mag.h" |
||
74 | #endif |
||
75 | |||
76 | #define FC_ADDRESS 1 |
||
77 | #define NC_ADDRESS 2 |
||
78 | #define MK3MAG_ADDRESS 3 |
||
79 | |||
80 | #define FALSE 0 |
||
81 | #define TRUE 1 |
||
82 | //int8_t test __attribute__ ((section (".noinit"))); |
||
1775 | - | 83 | uint8_t request_VerInfo = FALSE; |
84 | uint8_t request_ExternalControl = FALSE; |
||
85 | uint8_t request_Display = FALSE; |
||
86 | uint8_t request_Display1 = FALSE; |
||
87 | uint8_t request_DebugData = FALSE; |
||
88 | uint8_t request_Data3D = FALSE; |
||
89 | uint8_t request_DebugLabel = 255; |
||
90 | uint8_t request_PPMChannels = FALSE; |
||
91 | uint8_t request_MotorTest = FALSE; |
||
92 | uint8_t request_variables = FALSE; |
||
93 | |||
1612 | dongfang | 94 | uint8_t DisplayLine = 0; |
95 | |||
96 | volatile uint8_t txd_buffer[TXD_BUFFER_LEN]; |
||
97 | volatile uint8_t rxd_buffer_locked = FALSE; |
||
98 | volatile uint8_t rxd_buffer[RXD_BUFFER_LEN]; |
||
99 | volatile uint8_t txd_complete = TRUE; |
||
100 | volatile uint8_t ReceivedBytes = 0; |
||
101 | volatile uint8_t *pRxData = 0; |
||
102 | volatile uint8_t RxDataLen = 0; |
||
103 | |||
104 | uint8_t motorTestActive = 0; |
||
105 | uint8_t motorTest[16] = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}; |
||
106 | uint8_t ConfirmFrame; |
||
107 | |||
108 | typedef struct { |
||
109 | int16_t Heading; |
||
110 | } __attribute__((packed)) Heading_t; |
||
111 | |||
112 | DebugOut_t DebugOut; |
||
113 | Data3D_t Data3D; |
||
114 | UART_VersionInfo_t UART_VersionInfo; |
||
115 | |||
116 | uint16_t DebugData_Timer; |
||
117 | uint16_t Data3D_Timer; |
||
118 | uint16_t DebugData_Interval = 500; // in 1ms |
||
119 | uint16_t Data3D_Interval = 0; // in 1ms |
||
120 | |||
121 | #ifdef USE_MK3MAG |
||
122 | int16_t Compass_Timer; |
||
123 | #endif |
||
124 | |||
125 | // keep lables in flash to save 512 bytes of sram space |
||
126 | const prog_uint8_t ANALOG_LABEL[32][16] = { |
||
127 | //1234567890123456 |
||
128 | "AnglePitch ", //0 |
||
129 | "AngleRoll ", |
||
130 | "AngleYaw ", |
||
1646 | - | 131 | "GyroPitch(PID) ", |
132 | "GyroRoll(PID) ", |
||
133 | "GyroYaw ", //5 |
||
1645 | - | 134 | "GyroPitch(AC) ", |
135 | "GyroRoll(AC) ", |
||
1646 | - | 136 | "GyroYaw(AC) ", |
1775 | - | 137 | "AccPitch (angle)", |
138 | "AccRoll (angle) ", //10 |
||
139 | "UBat ", |
||
140 | "Pitch Term ", |
||
141 | "Roll Term ", |
||
142 | "Yaw Term ", |
||
143 | "Throttle Term ", //15 |
||
144 | "0th O Corr pitch", |
||
145 | "0th O Corr roll ", |
||
146 | "DriftCompDelta P", |
||
147 | "DriftCompDelta R", |
||
148 | "ADPitchGyroOffs ", //20 |
||
149 | "ADRollGyroOffs ", |
||
150 | "M1 ", |
||
151 | "M2 ", |
||
152 | "M3 ", |
||
153 | "M4 ", //25 |
||
154 | "ControlYaw ", |
||
155 | "Acc Z ", |
||
156 | "DriftCompPitch ", |
||
157 | "DriftCompRoll ", |
||
1612 | dongfang | 158 | "Pitch Noise ", //30 |
159 | "Roll Noise " |
||
160 | }; |
||
161 | |||
162 | /****************************************************************/ |
||
163 | /* Initialization of the USART0 */ |
||
164 | /****************************************************************/ |
||
1645 | - | 165 | void usart0_Init (void) { |
1612 | dongfang | 166 | uint8_t sreg = SREG; |
167 | uint16_t ubrr = (uint16_t) ((uint32_t) SYSCLK/(8 * USART0_BAUD) - 1); |
||
168 | |||
169 | // disable all interrupts before configuration |
||
170 | cli(); |
||
171 | |||
172 | // disable RX-Interrupt |
||
173 | UCSR0B &= ~(1 << RXCIE0); |
||
174 | // disable TX-Interrupt |
||
175 | UCSR0B &= ~(1 << TXCIE0); |
||
176 | |||
177 | // set direction of RXD0 and TXD0 pins |
||
178 | // set RXD0 (PD0) as an input pin |
||
179 | PORTD |= (1 << PORTD0); |
||
180 | DDRD &= ~(1 << DDD0); |
||
181 | // set TXD0 (PD1) as an output pin |
||
182 | PORTD |= (1 << PORTD1); |
||
183 | DDRD |= (1 << DDD1); |
||
184 | |||
185 | // USART0 Baud Rate Register |
||
186 | // set clock divider |
||
187 | UBRR0H = (uint8_t)(ubrr >> 8); |
||
188 | UBRR0L = (uint8_t)ubrr; |
||
189 | |||
190 | // USART0 Control and Status Register A, B, C |
||
191 | |||
192 | // enable double speed operation in |
||
193 | UCSR0A |= (1 << U2X0); |
||
194 | // enable receiver and transmitter in |
||
195 | UCSR0B = (1 << TXEN0) | (1 << RXEN0); |
||
196 | // set asynchronous mode |
||
197 | UCSR0C &= ~(1 << UMSEL01); |
||
198 | UCSR0C &= ~(1 << UMSEL00); |
||
199 | // no parity |
||
200 | UCSR0C &= ~(1 << UPM01); |
||
201 | UCSR0C &= ~(1 << UPM00); |
||
202 | // 1 stop bit |
||
203 | UCSR0C &= ~(1 << USBS0); |
||
204 | // 8-bit |
||
205 | UCSR0B &= ~(1 << UCSZ02); |
||
206 | UCSR0C |= (1 << UCSZ01); |
||
207 | UCSR0C |= (1 << UCSZ00); |
||
208 | |||
209 | // flush receive buffer |
||
210 | while ( UCSR0A & (1<<RXC0) ) UDR0; |
||
211 | |||
212 | // enable interrupts at the end |
||
213 | // enable RX-Interrupt |
||
214 | UCSR0B |= (1 << RXCIE0); |
||
215 | // enable TX-Interrupt |
||
216 | UCSR0B |= (1 << TXCIE0); |
||
217 | |||
218 | // initialize the debug timer |
||
219 | DebugData_Timer = SetDelay(DebugData_Interval); |
||
220 | |||
221 | // unlock rxd_buffer |
||
222 | rxd_buffer_locked = FALSE; |
||
223 | pRxData = 0; |
||
224 | RxDataLen = 0; |
||
225 | |||
226 | // no bytes to send |
||
227 | txd_complete = TRUE; |
||
228 | |||
229 | #ifdef USE_MK3MAG |
||
230 | Compass_Timer = SetDelay(220); |
||
231 | #endif |
||
232 | |||
233 | UART_VersionInfo.SWMajor = VERSION_MAJOR; |
||
234 | UART_VersionInfo.SWMinor = VERSION_MINOR; |
||
235 | UART_VersionInfo.SWPatch = VERSION_PATCH; |
||
236 | UART_VersionInfo.ProtoMajor = VERSION_SERIAL_MAJOR; |
||
237 | UART_VersionInfo.ProtoMinor = VERSION_SERIAL_MINOR; |
||
238 | |||
239 | // restore global interrupt flags |
||
240 | SREG = sreg; |
||
241 | } |
||
242 | |||
243 | /****************************************************************/ |
||
244 | /* USART0 transmitter ISR */ |
||
245 | /****************************************************************/ |
||
246 | ISR(USART0_TX_vect) { |
||
247 | static uint16_t ptr_txd_buffer = 0; |
||
248 | uint8_t tmp_tx; |
||
249 | if(!txd_complete) { // transmission not completed |
||
250 | ptr_txd_buffer++; // die [0] wurde schon gesendet |
||
251 | tmp_tx = txd_buffer[ptr_txd_buffer]; |
||
252 | // if terminating character or end of txd buffer was reached |
||
253 | if((tmp_tx == '\r') || (ptr_txd_buffer == TXD_BUFFER_LEN)) { |
||
254 | ptr_txd_buffer = 0; // reset txd pointer |
||
255 | txd_complete = 1; // stop transmission |
||
256 | } |
||
257 | UDR0 = tmp_tx; // send current byte will trigger this ISR again |
||
258 | } |
||
259 | // transmission completed |
||
260 | else ptr_txd_buffer = 0; |
||
261 | } |
||
262 | |||
263 | /****************************************************************/ |
||
264 | /* USART0 receiver ISR */ |
||
265 | /****************************************************************/ |
||
266 | ISR(USART0_RX_vect) { |
||
267 | static uint16_t crc; |
||
268 | static uint8_t ptr_rxd_buffer = 0; |
||
269 | uint8_t crc1, crc2; |
||
270 | uint8_t c; |
||
271 | |||
272 | c = UDR0; // catch the received byte |
||
273 | |||
274 | #if (defined (USE_MK3MAG)) |
||
275 | // If the cpu is not an Atmega644P the ublox module should be conneced to rxd of the 1st uart. |
||
276 | if(CPUType != ATMEGA644P) ubx_parser(c); |
||
277 | #endif |
||
278 | |||
279 | if(rxd_buffer_locked) return; // if rxd buffer is locked immediately return |
||
280 | |||
281 | // the rxd buffer is unlocked |
||
282 | if((ptr_rxd_buffer == 0) && (c == '#')) { // if rxd buffer is empty and syncronisation character is received |
||
283 | rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer |
||
284 | crc = c; // init crc |
||
285 | } |
||
286 | #if 0 |
||
287 | else if (ptr_rxd_buffer == 1) { // handle address |
||
288 | rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer |
||
289 | crc += c; // update crc |
||
290 | } |
||
291 | #endif |
||
292 | else if (ptr_rxd_buffer < RXD_BUFFER_LEN) { // collect incomming bytes |
||
293 | if(c != '\r') { // no termination character |
||
294 | rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer |
||
295 | crc += c; // update crc |
||
296 | } else { // termination character was received |
||
297 | // the last 2 bytes are no subject for checksum calculation |
||
298 | // they are the checksum itself |
||
299 | crc -= rxd_buffer[ptr_rxd_buffer-2]; |
||
300 | crc -= rxd_buffer[ptr_rxd_buffer-1]; |
||
301 | // calculate checksum from transmitted data |
||
302 | crc %= 4096; |
||
303 | crc1 = '=' + crc / 64; |
||
304 | crc2 = '=' + crc % 64; |
||
305 | // compare checksum to transmitted checksum bytes |
||
306 | if((crc1 == rxd_buffer[ptr_rxd_buffer-2]) && (crc2 == rxd_buffer[ptr_rxd_buffer-1])) { |
||
307 | // checksum valid |
||
308 | rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character |
||
309 | ReceivedBytes = ptr_rxd_buffer + 1;// store number of received bytes |
||
310 | rxd_buffer_locked = TRUE; // lock the rxd buffer |
||
311 | // if 2nd byte is an 'R' enable watchdog that will result in an reset |
||
312 | if(rxd_buffer[2] == 'R') {wdt_enable(WDTO_250MS);} // Reset-Commando |
||
313 | } else { // checksum invalid |
||
314 | rxd_buffer_locked = FALSE; // unlock rxd buffer |
||
315 | } |
||
316 | ptr_rxd_buffer = 0; // reset rxd buffer pointer |
||
317 | } |
||
318 | } else { // rxd buffer overrun |
||
319 | ptr_rxd_buffer = 0; // reset rxd buffer |
||
320 | rxd_buffer_locked = FALSE; // unlock rxd buffer |
||
321 | } |
||
322 | } |
||
323 | |||
324 | // -------------------------------------------------------------------------- |
||
325 | void AddCRC(uint16_t datalen) { |
||
326 | uint16_t tmpCRC = 0, i; |
||
327 | for(i = 0; i < datalen; i++) { |
||
328 | tmpCRC += txd_buffer[i]; |
||
329 | } |
||
330 | tmpCRC %= 4096; |
||
331 | txd_buffer[i++] = '=' + tmpCRC / 64; |
||
332 | txd_buffer[i++] = '=' + tmpCRC % 64; |
||
333 | txd_buffer[i++] = '\r'; |
||
334 | txd_complete = FALSE; |
||
335 | UDR0 = txd_buffer[0]; // initiates the transmittion (continued in the TXD ISR) |
||
336 | } |
||
337 | |||
338 | // -------------------------------------------------------------------------- |
||
1775 | - | 339 | // application example: |
340 | // SendOutData('A', FC_ADDRESS, 2, (uint8_t *)&request_DebugLabel, sizeof(request_DebugLabel), label, 16); |
||
341 | /* |
||
1612 | dongfang | 342 | void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) { // uint8_t *pdata, uint8_t len, ... |
343 | va_list ap; |
||
1775 | - | 344 | uint16_t txd_bufferIndex = 0; |
345 | uint8_t *currentBuffer; |
||
346 | uint8_t currentBufferIndex; |
||
347 | uint16_t lengthOfCurrentBuffer; |
||
348 | uint8_t shift = 0; |
||
349 | |||
350 | txd_buffer[txd_bufferIndex++] = '#'; // Start character |
||
351 | txd_buffer[txd_bufferIndex++] = 'a' + addr; // Address (a=0; b=1,...) |
||
352 | txd_buffer[txd_bufferIndex++] = cmd; // Command |
||
353 | |||
354 | va_start(ap, numofbuffers); |
||
355 | |||
356 | while(numofbuffers) { |
||
357 | currentBuffer = va_arg(ap, uint8_t*); |
||
358 | lengthOfCurrentBuffer = va_arg(ap, int); |
||
359 | currentBufferIndex = 0; |
||
360 | // Encode data: 3 bytes of data are encoded into 4 bytes, |
||
361 | // where the 2 most significant bits are both 0. |
||
362 | while(currentBufferIndex != lengthOfCurrentBuffer) { |
||
363 | if (!shift) txd_buffer[txd_bufferIndex] = 0; |
||
364 | txd_buffer[txd_bufferIndex] |= currentBuffer[currentBufferIndex] >> (shift + 2); |
||
365 | txd_buffer[++txd_bufferIndex] = (currentBuffer[currentBufferIndex] << (4 - shift)) & 0b00111111; |
||
366 | shift += 2; |
||
367 | if (shift == 6) { shift=0; txd_bufferIndex++; } |
||
368 | currentBufferIndex++; |
||
369 | } |
||
370 | } |
||
371 | // If the number of data bytes was not divisible by 3, stuff |
||
372 | // with 0 pseudodata until length is again divisible by 3. |
||
373 | if (shift == 2) { |
||
374 | // We need to stuff with zero bytes at the end. |
||
375 | txd_buffer[txd_bufferIndex] &= 0b00110000; |
||
376 | txd_buffer[++txd_bufferIndex] = 0; |
||
377 | shift = 4; |
||
378 | } |
||
379 | if (shift == 4) { |
||
380 | // We need to stuff with zero bytes at the end. |
||
381 | txd_buffer[txd_bufferIndex++] &= 0b00111100; |
||
382 | txd_buffer[txd_bufferIndex] = 0; |
||
383 | } |
||
384 | va_end(ap); |
||
385 | AddCRC(pt); // add checksum after data block and initates the transmission |
||
386 | } |
||
387 | */ |
||
388 | |||
389 | void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) { // uint8_t *pdata, uint8_t len, ... |
||
390 | va_list ap; |
||
1612 | dongfang | 391 | uint16_t pt = 0; |
392 | uint8_t a,b,c; |
||
393 | uint8_t ptr = 0; |
||
394 | |||
395 | uint8_t *pdata = 0; |
||
396 | int len = 0; |
||
397 | |||
398 | txd_buffer[pt++] = '#'; // Start character |
||
399 | txd_buffer[pt++] = 'a' + addr; // Address (a=0; b=1,...) |
||
400 | txd_buffer[pt++] = cmd; // Command |
||
401 | |||
402 | va_start(ap, numofbuffers); |
||
403 | |||
404 | if(numofbuffers) { |
||
405 | pdata = va_arg(ap, uint8_t*); |
||
406 | len = va_arg(ap, int); |
||
407 | ptr = 0; |
||
408 | numofbuffers--; |
||
409 | } |
||
410 | |||
411 | while(len){ |
||
412 | if(len) { |
||
413 | a = pdata[ptr++]; |
||
414 | len--; |
||
415 | if((!len) && numofbuffers) { |
||
416 | pdata = va_arg(ap, uint8_t*); |
||
417 | len = va_arg(ap, int); |
||
418 | ptr = 0; |
||
419 | numofbuffers--; |
||
420 | } |
||
421 | } |
||
422 | else a = 0; |
||
423 | if(len) { |
||
424 | b = pdata[ptr++]; |
||
425 | len--; |
||
426 | if((!len) && numofbuffers) { |
||
427 | pdata = va_arg(ap, uint8_t*); |
||
428 | len = va_arg(ap, int); |
||
429 | ptr = 0; |
||
430 | numofbuffers--; |
||
431 | } |
||
432 | } else b = 0; |
||
433 | if(len) { |
||
434 | c = pdata[ptr++]; |
||
435 | len--; |
||
436 | if((!len) && numofbuffers) { |
||
437 | pdata = va_arg(ap, uint8_t*); |
||
438 | len = va_arg(ap, int); |
||
439 | ptr = 0; |
||
440 | numofbuffers--; |
||
441 | } |
||
442 | } |
||
443 | else c = 0; |
||
444 | txd_buffer[pt++] = '=' + (a >> 2); |
||
445 | txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4)); |
||
446 | txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6)); |
||
447 | txd_buffer[pt++] = '=' + ( c & 0x3f); |
||
448 | } |
||
449 | va_end(ap); |
||
450 | AddCRC(pt); // add checksum after data block and initates the transmission |
||
451 | } |
||
452 | |||
453 | // -------------------------------------------------------------------------- |
||
454 | void Decode64(void) { |
||
455 | uint8_t a,b,c,d; |
||
456 | uint8_t x,y,z; |
||
457 | uint8_t ptrIn = 3; |
||
458 | uint8_t ptrOut = 3; |
||
459 | uint8_t len = ReceivedBytes - 6; |
||
460 | |||
461 | while(len) { |
||
462 | a = rxd_buffer[ptrIn++] - '='; |
||
463 | b = rxd_buffer[ptrIn++] - '='; |
||
464 | c = rxd_buffer[ptrIn++] - '='; |
||
465 | d = rxd_buffer[ptrIn++] - '='; |
||
466 | //if(ptrIn > ReceivedBytes - 3) break; |
||
467 | |||
468 | x = (a << 2) | (b >> 4); |
||
469 | y = ((b & 0x0f) << 4) | (c >> 2); |
||
470 | z = ((c & 0x03) << 6) | d; |
||
471 | |||
472 | if(len--) rxd_buffer[ptrOut++] = x; else break; |
||
473 | if(len--) rxd_buffer[ptrOut++] = y; else break; |
||
474 | if(len--) rxd_buffer[ptrOut++] = z; else break; |
||
475 | } |
||
476 | pRxData = &rxd_buffer[3]; |
||
477 | RxDataLen = ptrOut - 3; |
||
478 | } |
||
479 | |||
480 | // -------------------------------------------------------------------------- |
||
1645 | - | 481 | void usart0_ProcessRxData(void) { |
1775 | - | 482 | // We control the motorTestActive var from here: Count it down. |
483 | if (motorTestActive) motorTestActive--; |
||
1612 | dongfang | 484 | // if data in the rxd buffer are not locked immediately return |
485 | if(!rxd_buffer_locked) return; |
||
486 | uint8_t tempchar1, tempchar2; |
||
487 | Decode64(); // decode data block in rxd_buffer |
||
1775 | - | 488 | |
1612 | dongfang | 489 | switch(rxd_buffer[1] - 'a') { |
1775 | - | 490 | |
1612 | dongfang | 491 | case FC_ADDRESS: |
492 | switch(rxd_buffer[2]) { |
||
493 | #ifdef USE_MK3MAG |
||
494 | case 'K':// compass value |
||
1775 | - | 495 | compassHeading = ((Heading_t *)pRxData)->Heading; |
496 | compassOffCourse = ((540 + compassHeading - compassCourse) % 360) - 180; |
||
1612 | dongfang | 497 | break; |
498 | #endif |
||
1775 | - | 499 | case 't': // motor test |
500 | if(RxDataLen > 20) { |
||
501 | memcpy(&motorTest[0], (uint8_t*)pRxData, sizeof(motorTest)); |
||
502 | } else { |
||
503 | memcpy(&motorTest[0], (uint8_t*)pRxData, 4); |
||
504 | } |
||
1612 | dongfang | 505 | motorTestActive = 255; |
506 | externalControlActive = 255; |
||
507 | break; |
||
508 | |||
509 | case 'n':// "Get Mixer Table |
||
510 | while(!txd_complete); // wait for previous frame to be sent |
||
511 | SendOutData('N', FC_ADDRESS, 1, (uint8_t *) &Mixer, sizeof(Mixer)); |
||
512 | break; |
||
513 | |||
514 | case 'm':// "Set Mixer Table |
||
1775 | - | 515 | if(pRxData[0] == EEMIXER_REVISION) { |
516 | memcpy(&Mixer, (uint8_t*)pRxData, sizeof(Mixer)); |
||
517 | MixerTable_WriteToEEProm(); |
||
518 | while(!txd_complete); // wait for previous frame to be sent |
||
519 | tempchar1 = 1; |
||
520 | } else { |
||
521 | tempchar1 = 0; |
||
522 | } |
||
1612 | dongfang | 523 | SendOutData('M', FC_ADDRESS, 1, &tempchar1, 1); |
524 | break; |
||
525 | |||
526 | case 'p': // get PPM channels |
||
1775 | - | 527 | request_PPMChannels = TRUE; |
1612 | dongfang | 528 | break; |
529 | |||
530 | case 'q':// request settings |
||
1775 | - | 531 | if(pRxData[0] == 0xFF) { |
532 | pRxData[0] = GetParamByte(PID_ACTIVE_SET); |
||
533 | } |
||
1612 | dongfang | 534 | // limit settings range |
535 | if(pRxData[0] < 1) pRxData[0] = 1; // limit to 1 |
||
536 | else if(pRxData[0] > 5) pRxData[0] = 5; // limit to 5 |
||
537 | // load requested parameter set |
||
538 | ParamSet_ReadFromEEProm(pRxData[0]); |
||
539 | tempchar1 = pRxData[0]; |
||
540 | tempchar2 = EEPARAM_REVISION; |
||
541 | while(!txd_complete); // wait for previous frame to be sent |
||
542 | SendOutData('Q', FC_ADDRESS,3, &tempchar1, sizeof(tempchar1), &tempchar2, sizeof(tempchar2), (uint8_t *) &staticParams, sizeof(staticParams)); |
||
543 | break; |
||
544 | |||
545 | case 's': // save settings |
||
546 | if(!(MKFlags & MKFLAG_MOTOR_RUN)) // save settings only if motors ar off |
||
547 | { |
||
548 | if((1 <= pRxData[0]) && (pRxData[0] <= 5) && (pRxData[1] == EEPARAM_REVISION)) // check for setting to be in range and version of settings |
||
549 | { |
||
550 | memcpy(&staticParams, (uint8_t*)&pRxData[2], sizeof(staticParams)); |
||
551 | ParamSet_WriteToEEProm(pRxData[0]); |
||
552 | /* |
||
553 | TODO: Remove this encapsulation breach |
||
554 | turnOver180Pitch = (int32_t) staticParams.AngleTurnOverPitch * 2500L; |
||
555 | turnOver180Roll = (int32_t) staticParams.AngleTurnOverRoll * 2500L; |
||
556 | */ |
||
557 | tempchar1 = getActiveParamSet(); |
||
558 | beepNumber(tempchar1); |
||
559 | } |
||
560 | else |
||
561 | { |
||
562 | tempchar1 = 0; //indicate bad data |
||
563 | } |
||
564 | while(!txd_complete); // wait for previous frame to be sent |
||
565 | SendOutData('S', FC_ADDRESS,1, &tempchar1, sizeof(tempchar1)); |
||
566 | } |
||
567 | break; |
||
568 | |||
569 | default: |
||
570 | //unsupported command received |
||
571 | break; |
||
572 | } // case FC_ADDRESS: |
||
573 | |||
574 | default: // any Slave Address |
||
1775 | - | 575 | switch(rxd_buffer[2]) { |
1612 | dongfang | 576 | case 'a':// request for labels of the analog debug outputs |
1775 | - | 577 | request_DebugLabel = pRxData[0]; |
578 | if(request_DebugLabel > 31) request_DebugLabel = 31; |
||
1612 | dongfang | 579 | externalControlActive = 255; |
580 | break; |
||
581 | |||
582 | case 'b': // submit extern control |
||
583 | memcpy(&externalControl, (uint8_t*)pRxData, sizeof(externalControl)); |
||
584 | ConfirmFrame = externalControl.frame; |
||
585 | externalControlActive = 255; |
||
586 | break; |
||
587 | |||
588 | case 'h':// request for display columns |
||
589 | externalControlActive = 255; |
||
590 | RemoteKeys |= pRxData[0]; |
||
591 | if(RemoteKeys) DisplayLine = 0; |
||
1775 | - | 592 | request_Display = TRUE; |
1612 | dongfang | 593 | break; |
594 | |||
595 | case 'l':// request for display columns |
||
596 | externalControlActive = 255; |
||
597 | MenuItem = pRxData[0]; |
||
1775 | - | 598 | request_Display1 = TRUE; |
1612 | dongfang | 599 | break; |
600 | |||
601 | case 'v': // request for version and board release |
||
1775 | - | 602 | request_VerInfo = TRUE; |
1612 | dongfang | 603 | break; |
604 | |||
1775 | - | 605 | case 'x': |
606 | request_variables = TRUE; |
||
607 | break; |
||
608 | |||
1612 | dongfang | 609 | case 'g':// get external control data |
1775 | - | 610 | request_ExternalControl = TRUE; |
1612 | dongfang | 611 | break; |
612 | |||
613 | case 'd': // request for the debug data |
||
614 | DebugData_Interval = (uint16_t) pRxData[0] * 10; |
||
1775 | - | 615 | if(DebugData_Interval > 0) request_DebugData = TRUE; |
1612 | dongfang | 616 | break; |
617 | |||
618 | case 'c': // request for the 3D data |
||
619 | Data3D_Interval = (uint16_t) pRxData[0] * 10; |
||
1775 | - | 620 | if(Data3D_Interval > 0) request_Data3D = TRUE; |
1612 | dongfang | 621 | break; |
622 | |||
623 | default: |
||
624 | //unsupported command received |
||
625 | break; |
||
626 | } |
||
627 | break; // default: |
||
628 | } |
||
629 | // unlock the rxd buffer after processing |
||
630 | pRxData = 0; |
||
631 | RxDataLen = 0; |
||
632 | rxd_buffer_locked = FALSE; |
||
633 | } |
||
634 | |||
1645 | - | 635 | /************************************************************************/ |
636 | /* Routine für die Serielle Ausgabe */ |
||
637 | /************************************************************************/ |
||
1612 | dongfang | 638 | int16_t uart_putchar (int8_t c) { |
639 | if (c == '\n') |
||
640 | uart_putchar('\r'); |
||
641 | // wait until previous character was send |
||
642 | loop_until_bit_is_set(UCSR0A, UDRE0); |
||
643 | // send character |
||
644 | UDR0 = c; |
||
645 | return (0); |
||
646 | } |
||
647 | |||
648 | //--------------------------------------------------------------------------------------------- |
||
1645 | - | 649 | void usart0_TransmitTxData(void) { |
1612 | dongfang | 650 | if(!txd_complete) return; |
651 | |||
1775 | - | 652 | if(request_VerInfo && txd_complete) { |
1612 | dongfang | 653 | SendOutData('V', FC_ADDRESS, 1, (uint8_t *) &UART_VersionInfo, sizeof(UART_VersionInfo)); |
1775 | - | 654 | request_VerInfo = FALSE; |
1612 | dongfang | 655 | } |
656 | |||
1775 | - | 657 | if(request_Display && txd_complete) { |
1612 | dongfang | 658 | LCD_PrintMenu(); |
659 | SendOutData('H', FC_ADDRESS, 2, &DisplayLine, sizeof(DisplayLine), &DisplayBuff[DisplayLine * 20], 20); |
||
660 | DisplayLine++; |
||
661 | if(DisplayLine >= 4) DisplayLine = 0; |
||
1775 | - | 662 | request_Display = FALSE; |
1612 | dongfang | 663 | } |
664 | |||
1775 | - | 665 | if(request_Display1 && txd_complete) { |
1612 | dongfang | 666 | LCD_PrintMenu(); |
667 | SendOutData('L', FC_ADDRESS, 3, &MenuItem, sizeof(MenuItem), &MaxMenuItem, sizeof(MaxMenuItem), DisplayBuff, sizeof(DisplayBuff)); |
||
1775 | - | 668 | request_Display1 = FALSE; |
1612 | dongfang | 669 | } |
670 | |||
1775 | - | 671 | if(request_DebugLabel != 0xFF) { // Texte für die Analogdaten |
1612 | dongfang | 672 | uint8_t label[16]; // local sram buffer |
1775 | - | 673 | memcpy_P(label, ANALOG_LABEL[request_DebugLabel], 16); // read lable from flash to sram buffer |
674 | SendOutData('A', FC_ADDRESS, 2, (uint8_t *) &request_DebugLabel, sizeof(request_DebugLabel), label, 16); |
||
675 | request_DebugLabel = 0xFF; |
||
1612 | dongfang | 676 | } |
677 | |||
1645 | - | 678 | if(ConfirmFrame && txd_complete) { // Datensatz ohne CRC bestätigen |
1612 | dongfang | 679 | SendOutData('B', FC_ADDRESS, 1, (uint8_t*)&ConfirmFrame, sizeof(ConfirmFrame)); |
680 | ConfirmFrame = 0; |
||
681 | } |
||
682 | |||
1775 | - | 683 | if(((DebugData_Interval && CheckDelay(DebugData_Timer)) || request_DebugData) && txd_complete) { |
1612 | dongfang | 684 | SendOutData('D', FC_ADDRESS, 1,(uint8_t *) &DebugOut, sizeof(DebugOut)); |
685 | DebugData_Timer = SetDelay(DebugData_Interval); |
||
1775 | - | 686 | request_DebugData = FALSE; |
1612 | dongfang | 687 | } |
688 | |||
1775 | - | 689 | if( ((Data3D_Interval && CheckDelay(Data3D_Timer)) || request_Data3D) && txd_complete) { |
1612 | dongfang | 690 | SendOutData('C', FC_ADDRESS, 1,(uint8_t *) &Data3D, sizeof(Data3D)); |
1645 | - | 691 | Data3D.AngleNick = (int16_t)((10 * angle[PITCH]) / GYRO_DEG_FACTOR_PITCHROLL); // convert to multiple of 0.1° |
692 | Data3D.AngleRoll = (int16_t)((10 * angle[ROLL]) / GYRO_DEG_FACTOR_PITCHROLL); // convert to multiple of 0.1° |
||
1612 | dongfang | 693 | Data3D.Heading = (int16_t)((10 * yawGyroHeading) / GYRO_DEG_FACTOR_YAW); // convert to multiple of 0.1° |
694 | Data3D_Timer = SetDelay(Data3D_Interval); |
||
1775 | - | 695 | request_Data3D = FALSE; |
1612 | dongfang | 696 | } |
697 | |||
1775 | - | 698 | if(request_ExternalControl && txd_complete) { |
1612 | dongfang | 699 | SendOutData('G', FC_ADDRESS, 1,(uint8_t *) &externalControl, sizeof(externalControl)); |
1775 | - | 700 | request_ExternalControl = FALSE; |
1612 | dongfang | 701 | } |
702 | |||
703 | #ifdef USE_MK3MAG |
||
704 | if((CheckDelay(Compass_Timer)) && txd_complete) { |
||
1775 | - | 705 | ToMk3Mag.Attitude[0] = (int16_t)((10 * angle[PITCH]) / GYRO_DEG_FACTOR_PITCHROLL); // approx. 0.1 deg |
706 | ToMk3Mag.Attitude[1] = (int16_t)((10 * angle[ROLL]) / GYRO_DEG_FACTOR_PITCHROLL); // approx. 0.1 deg |
||
1612 | dongfang | 707 | ToMk3Mag.UserParam[0] = dynamicParams.UserParams[0]; |
708 | ToMk3Mag.UserParam[1] = dynamicParams.UserParams[1]; |
||
1775 | - | 709 | ToMk3Mag.CalState = compassCalState; |
1612 | dongfang | 710 | SendOutData('w', MK3MAG_ADDRESS, 1,(uint8_t *) &ToMk3Mag,sizeof(ToMk3Mag)); |
711 | // the last state is 5 and should be send only once to avoid multiple flash writing |
||
1775 | - | 712 | if(compassCalState > 4) compassCalState = 0; |
1612 | dongfang | 713 | Compass_Timer = SetDelay(99); |
714 | } |
||
715 | #endif |
||
716 | |||
1775 | - | 717 | if(request_MotorTest && txd_complete) { |
1612 | dongfang | 718 | SendOutData('T', FC_ADDRESS, 0); |
1775 | - | 719 | request_MotorTest = FALSE; |
1612 | dongfang | 720 | } |
721 | |||
1775 | - | 722 | if(request_PPMChannels && txd_complete) { |
1612 | dongfang | 723 | SendOutData('P', FC_ADDRESS, 1, (uint8_t *)&PPM_in, sizeof(PPM_in)); |
1775 | - | 724 | request_PPMChannels = FALSE; |
1612 | dongfang | 725 | } |
1775 | - | 726 | |
727 | if (request_variables && txd_complete) { |
||
728 | SendOutData('X', FC_ADDRESS, 1, (uint8_t *)&variables, sizeof(variables)); |
||
729 | request_variables = FALSE; |
||
730 | } |
||
1612 | dongfang | 731 | } |