Rev 1955 | Rev 1963 | 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) |
||
1868 | - | 35 | // + Commercial use (for example: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted |
1612 | dongfang | 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 "rc.h" |
||
65 | #include "externalControl.h" |
||
1775 | - | 66 | #include "output.h" |
1864 | - | 67 | #include "attitude.h" |
1612 | dongfang | 68 | |
1864 | - | 69 | |
1612 | dongfang | 70 | #ifdef USE_MK3MAG |
71 | #include "mk3mag.h" |
||
72 | #endif |
||
73 | |||
74 | #define FC_ADDRESS 1 |
||
75 | #define NC_ADDRESS 2 |
||
76 | #define MK3MAG_ADDRESS 3 |
||
77 | |||
78 | #define FALSE 0 |
||
79 | #define TRUE 1 |
||
80 | //int8_t test __attribute__ ((section (".noinit"))); |
||
1821 | - | 81 | uint8_t request_VerInfo = FALSE; |
82 | uint8_t request_ExternalControl = FALSE; |
||
83 | uint8_t request_Display = FALSE; |
||
84 | uint8_t request_Display1 = FALSE; |
||
85 | uint8_t request_DebugData = FALSE; |
||
86 | uint8_t request_Data3D = FALSE; |
||
87 | uint8_t request_DebugLabel = 255; |
||
88 | uint8_t request_PPMChannels = FALSE; |
||
89 | uint8_t request_MotorTest = FALSE; |
||
90 | uint8_t request_variables = FALSE; |
||
1775 | - | 91 | |
1612 | dongfang | 92 | uint8_t DisplayLine = 0; |
93 | |||
94 | volatile uint8_t txd_buffer[TXD_BUFFER_LEN]; |
||
95 | volatile uint8_t rxd_buffer_locked = FALSE; |
||
96 | volatile uint8_t rxd_buffer[RXD_BUFFER_LEN]; |
||
97 | volatile uint8_t txd_complete = TRUE; |
||
98 | volatile uint8_t ReceivedBytes = 0; |
||
99 | volatile uint8_t *pRxData = 0; |
||
100 | volatile uint8_t RxDataLen = 0; |
||
101 | |||
1821 | - | 102 | uint8_t motorTestActive = 0; |
103 | uint8_t motorTest[16] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; |
||
1612 | dongfang | 104 | uint8_t ConfirmFrame; |
105 | |||
106 | typedef struct { |
||
1821 | - | 107 | int16_t Heading; |
108 | }__attribute__((packed)) Heading_t; |
||
1612 | dongfang | 109 | |
1955 | - | 110 | DebugOut_t debugOut; |
1821 | - | 111 | Data3D_t Data3D; |
112 | UART_VersionInfo_t UART_VersionInfo; |
||
1612 | dongfang | 113 | |
114 | uint16_t DebugData_Timer; |
||
115 | uint16_t Data3D_Timer; |
||
116 | uint16_t DebugData_Interval = 500; // in 1ms |
||
117 | uint16_t Data3D_Interval = 0; // in 1ms |
||
118 | |||
119 | #ifdef USE_MK3MAG |
||
120 | int16_t Compass_Timer; |
||
121 | #endif |
||
122 | |||
123 | // keep lables in flash to save 512 bytes of sram space |
||
124 | const prog_uint8_t ANALOG_LABEL[32][16] = { |
||
1821 | - | 125 | //1234567890123456 |
126 | "AnglePitch ", //0 |
||
127 | "AngleRoll ", |
||
128 | "AngleYaw ", |
||
129 | "GyroPitch(PID) ", |
||
130 | "GyroRoll(PID) ", |
||
131 | "GyroYaw ", //5 |
||
1960 | - | 132 | "OffsPitch ", |
133 | "OffsRoll ", |
||
1887 | - | 134 | "AttitudeControl ", |
1821 | - | 135 | "AccPitch (angle)", |
136 | "AccRoll (angle) ", //10 |
||
1869 | - | 137 | "UBat ", |
1821 | - | 138 | "Pitch Term ", |
139 | "Roll Term ", |
||
1955 | - | 140 | "Yaw Term ", |
1908 | - | 141 | "ca debug ", //15 |
1955 | - | 142 | "gyroP ", |
143 | "gyroI ", |
||
144 | "gyroD ", |
||
1872 | - | 145 | "unused ", |
1869 | - | 146 | "dHeightThrottle ", //20 |
147 | "hoverThrottle ", |
||
1864 | - | 148 | "M1 ", |
149 | "M2 ", |
||
1821 | - | 150 | "M3 ", |
151 | "M4 ", //25 |
||
1864 | - | 152 | "ControlYaw ", |
153 | "Airpress. Range ", |
||
154 | "DriftCompPitch ", |
||
155 | "DriftCompRoll ", |
||
156 | "AirpressFiltered", //30 |
||
1821 | - | 157 | "AirpressADC " }; |
1612 | dongfang | 158 | |
159 | /****************************************************************/ |
||
160 | /* Initialization of the USART0 */ |
||
161 | /****************************************************************/ |
||
1821 | - | 162 | void usart0_Init(void) { |
163 | uint8_t sreg = SREG; |
||
164 | uint16_t ubrr = (uint16_t) ((uint32_t) SYSCLK / (8 * USART0_BAUD) - 1); |
||
165 | |||
166 | // disable all interrupts before configuration |
||
167 | cli(); |
||
168 | |||
169 | // disable RX-Interrupt |
||
170 | UCSR0B &= ~(1 << RXCIE0); |
||
171 | // disable TX-Interrupt |
||
172 | UCSR0B &= ~(1 << TXCIE0); |
||
173 | |||
174 | // set direction of RXD0 and TXD0 pins |
||
175 | // set RXD0 (PD0) as an input pin |
||
176 | PORTD |= (1 << PORTD0); |
||
177 | DDRD &= ~(1 << DDD0); |
||
178 | // set TXD0 (PD1) as an output pin |
||
179 | PORTD |= (1 << PORTD1); |
||
180 | DDRD |= (1 << DDD1); |
||
181 | |||
182 | // USART0 Baud Rate Register |
||
183 | // set clock divider |
||
184 | UBRR0H = (uint8_t) (ubrr >> 8); |
||
185 | UBRR0L = (uint8_t) ubrr; |
||
186 | |||
187 | // USART0 Control and Status Register A, B, C |
||
188 | |||
189 | // enable double speed operation in |
||
190 | UCSR0A |= (1 << U2X0); |
||
191 | // enable receiver and transmitter in |
||
192 | UCSR0B = (1 << TXEN0) | (1 << RXEN0); |
||
193 | // set asynchronous mode |
||
194 | UCSR0C &= ~(1 << UMSEL01); |
||
195 | UCSR0C &= ~(1 << UMSEL00); |
||
196 | // no parity |
||
197 | UCSR0C &= ~(1 << UPM01); |
||
198 | UCSR0C &= ~(1 << UPM00); |
||
199 | // 1 stop bit |
||
200 | UCSR0C &= ~(1 << USBS0); |
||
201 | // 8-bit |
||
202 | UCSR0B &= ~(1 << UCSZ02); |
||
203 | UCSR0C |= (1 << UCSZ01); |
||
204 | UCSR0C |= (1 << UCSZ00); |
||
205 | |||
206 | // flush receive buffer |
||
207 | while (UCSR0A & (1 << RXC0)) |
||
208 | UDR0; |
||
209 | |||
210 | // enable interrupts at the end |
||
211 | // enable RX-Interrupt |
||
212 | UCSR0B |= (1 << RXCIE0); |
||
213 | // enable TX-Interrupt |
||
214 | UCSR0B |= (1 << TXCIE0); |
||
215 | |||
216 | // initialize the debug timer |
||
1887 | - | 217 | DebugData_Timer = setDelay(DebugData_Interval); |
1821 | - | 218 | |
219 | // unlock rxd_buffer |
||
220 | rxd_buffer_locked = FALSE; |
||
221 | pRxData = 0; |
||
222 | RxDataLen = 0; |
||
223 | |||
224 | // no bytes to send |
||
225 | txd_complete = TRUE; |
||
226 | |||
1612 | dongfang | 227 | #ifdef USE_MK3MAG |
1887 | - | 228 | Compass_Timer = setDelay(220); |
1612 | dongfang | 229 | #endif |
1821 | - | 230 | |
231 | UART_VersionInfo.SWMajor = VERSION_MAJOR; |
||
232 | UART_VersionInfo.SWMinor = VERSION_MINOR; |
||
233 | UART_VersionInfo.SWPatch = VERSION_PATCH; |
||
234 | UART_VersionInfo.ProtoMajor = VERSION_SERIAL_MAJOR; |
||
235 | UART_VersionInfo.ProtoMinor = VERSION_SERIAL_MINOR; |
||
236 | |||
237 | // restore global interrupt flags |
||
238 | SREG = sreg; |
||
1612 | dongfang | 239 | } |
240 | |||
241 | /****************************************************************/ |
||
242 | /* USART0 transmitter ISR */ |
||
243 | /****************************************************************/ |
||
1821 | - | 244 | ISR(USART0_TX_vect) |
245 | { |
||
246 | static uint16_t ptr_txd_buffer = 0; |
||
247 | uint8_t tmp_tx; |
||
248 | if (!txd_complete) { // transmission not completed |
||
249 | ptr_txd_buffer++; // die [0] wurde schon gesendet |
||
250 | tmp_tx = txd_buffer[ptr_txd_buffer]; |
||
251 | // if terminating character or end of txd buffer was reached |
||
252 | if ((tmp_tx == '\r') || (ptr_txd_buffer == TXD_BUFFER_LEN)) { |
||
253 | ptr_txd_buffer = 0; // reset txd pointer |
||
254 | txd_complete = 1; // stop transmission |
||
255 | } |
||
256 | UDR0 = tmp_tx; // send current byte will trigger this ISR again |
||
257 | } |
||
258 | // transmission completed |
||
259 | else |
||
260 | ptr_txd_buffer = 0; |
||
1612 | dongfang | 261 | } |
262 | |||
263 | /****************************************************************/ |
||
264 | /* USART0 receiver ISR */ |
||
265 | /****************************************************************/ |
||
1821 | - | 266 | ISR(USART0_RX_vect) |
267 | { |
||
268 | static uint16_t crc; |
||
269 | static uint8_t ptr_rxd_buffer = 0; |
||
270 | uint8_t crc1, crc2; |
||
271 | uint8_t c; |
||
1612 | dongfang | 272 | |
1821 | - | 273 | c = UDR0; // catch the received byte |
1612 | dongfang | 274 | |
1821 | - | 275 | if (rxd_buffer_locked) |
276 | return; // if rxd buffer is locked immediately return |
||
1612 | dongfang | 277 | |
1821 | - | 278 | // the rxd buffer is unlocked |
279 | if ((ptr_rxd_buffer == 0) && (c == '#')) { // if rxd buffer is empty and syncronisation character is received |
||
280 | rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer |
||
281 | crc = c; // init crc |
||
282 | } |
||
1612 | dongfang | 283 | #if 0 |
1821 | - | 284 | else if (ptr_rxd_buffer == 1) { // handle address |
285 | rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer |
||
286 | crc += c; // update crc |
||
287 | } |
||
1612 | dongfang | 288 | #endif |
1821 | - | 289 | else if (ptr_rxd_buffer < RXD_BUFFER_LEN) { // collect incomming bytes |
290 | if (c != '\r') { // no termination character |
||
291 | rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer |
||
292 | crc += c; // update crc |
||
293 | } else { // termination character was received |
||
294 | // the last 2 bytes are no subject for checksum calculation |
||
295 | // they are the checksum itself |
||
296 | crc -= rxd_buffer[ptr_rxd_buffer - 2]; |
||
297 | crc -= rxd_buffer[ptr_rxd_buffer - 1]; |
||
298 | // calculate checksum from transmitted data |
||
299 | crc %= 4096; |
||
300 | crc1 = '=' + crc / 64; |
||
301 | crc2 = '=' + crc % 64; |
||
302 | // compare checksum to transmitted checksum bytes |
||
303 | if ((crc1 == rxd_buffer[ptr_rxd_buffer - 2]) && (crc2 |
||
304 | == rxd_buffer[ptr_rxd_buffer - 1])) { |
||
305 | // checksum valid |
||
306 | rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character |
||
307 | ReceivedBytes = ptr_rxd_buffer + 1;// store number of received bytes |
||
308 | rxd_buffer_locked = TRUE; // lock the rxd buffer |
||
309 | // if 2nd byte is an 'R' enable watchdog that will result in an reset |
||
310 | if (rxd_buffer[2] == 'R') { |
||
311 | wdt_enable(WDTO_250MS); |
||
312 | } // 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 | } |
||
1612 | dongfang | 322 | } |
323 | |||
324 | // -------------------------------------------------------------------------- |
||
325 | void AddCRC(uint16_t datalen) { |
||
1821 | - | 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) |
||
1612 | dongfang | 336 | } |
337 | |||
338 | // -------------------------------------------------------------------------- |
||
1775 | - | 339 | // application example: |
340 | // SendOutData('A', FC_ADDRESS, 2, (uint8_t *)&request_DebugLabel, sizeof(request_DebugLabel), label, 16); |
||
341 | /* |
||
1821 | - | 342 | void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) { // uint8_t *pdata, uint8_t len, ... |
343 | va_list ap; |
||
344 | uint16_t txd_bufferIndex = 0; |
||
345 | uint8_t *currentBuffer; |
||
346 | uint8_t currentBufferIndex; |
||
347 | uint16_t lengthOfCurrentBuffer; |
||
348 | uint8_t shift = 0; |
||
1775 | - | 349 | |
1821 | - | 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 |
||
1775 | - | 353 | |
1821 | - | 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 | |||
1775 | - | 389 | void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) { // uint8_t *pdata, uint8_t len, ... |
1821 | - | 390 | va_list ap; |
391 | uint16_t pt = 0; |
||
392 | uint8_t a, b, c; |
||
393 | uint8_t ptr = 0; |
||
1612 | dongfang | 394 | |
1821 | - | 395 | uint8_t *pdata = 0; |
396 | int len = 0; |
||
1612 | dongfang | 397 | |
1821 | - | 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 | } else |
||
422 | 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 |
||
433 | b = 0; |
||
434 | if (len) { |
||
435 | c = pdata[ptr++]; |
||
436 | len--; |
||
437 | if ((!len) && numofbuffers) { |
||
438 | pdata = va_arg(ap, uint8_t*); |
||
439 | len = va_arg(ap, int); |
||
440 | ptr = 0; |
||
441 | numofbuffers--; |
||
442 | } |
||
443 | } else |
||
444 | c = 0; |
||
445 | txd_buffer[pt++] = '=' + (a >> 2); |
||
446 | txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4)); |
||
447 | txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6)); |
||
448 | txd_buffer[pt++] = '=' + (c & 0x3f); |
||
449 | } |
||
450 | va_end(ap); |
||
451 | AddCRC(pt); // add checksum after data block and initates the transmission |
||
1612 | dongfang | 452 | } |
453 | |||
454 | // -------------------------------------------------------------------------- |
||
455 | void Decode64(void) { |
||
1821 | - | 456 | uint8_t a, b, c, d; |
457 | uint8_t x, y, z; |
||
458 | uint8_t ptrIn = 3; |
||
459 | uint8_t ptrOut = 3; |
||
460 | uint8_t len = ReceivedBytes - 6; |
||
461 | |||
462 | while (len) { |
||
463 | a = rxd_buffer[ptrIn++] - '='; |
||
464 | b = rxd_buffer[ptrIn++] - '='; |
||
465 | c = rxd_buffer[ptrIn++] - '='; |
||
466 | d = rxd_buffer[ptrIn++] - '='; |
||
467 | //if(ptrIn > ReceivedBytes - 3) break; |
||
468 | |||
469 | x = (a << 2) | (b >> 4); |
||
470 | y = ((b & 0x0f) << 4) | (c >> 2); |
||
471 | z = ((c & 0x03) << 6) | d; |
||
472 | |||
473 | if (len--) |
||
474 | rxd_buffer[ptrOut++] = x; |
||
475 | else |
||
476 | break; |
||
477 | if (len--) |
||
478 | rxd_buffer[ptrOut++] = y; |
||
479 | else |
||
480 | break; |
||
481 | if (len--) |
||
482 | rxd_buffer[ptrOut++] = z; |
||
483 | else |
||
484 | break; |
||
485 | } |
||
486 | pRxData = &rxd_buffer[3]; |
||
487 | RxDataLen = ptrOut - 3; |
||
1612 | dongfang | 488 | } |
489 | |||
490 | // -------------------------------------------------------------------------- |
||
1645 | - | 491 | void usart0_ProcessRxData(void) { |
1821 | - | 492 | // We control the motorTestActive var from here: Count it down. |
493 | if (motorTestActive) |
||
494 | motorTestActive--; |
||
495 | // if data in the rxd buffer are not locked immediately return |
||
496 | if (!rxd_buffer_locked) |
||
497 | return; |
||
498 | uint8_t tempchar1, tempchar2; |
||
499 | Decode64(); // decode data block in rxd_buffer |
||
1775 | - | 500 | |
1821 | - | 501 | switch (rxd_buffer[1] - 'a') { |
1775 | - | 502 | |
1821 | - | 503 | case FC_ADDRESS: |
504 | switch (rxd_buffer[2]) { |
||
1612 | dongfang | 505 | #ifdef USE_MK3MAG |
1821 | - | 506 | case 'K':// compass value |
507 | compassHeading = ((Heading_t *)pRxData)->Heading; |
||
508 | // compassOffCourse = ((540 + compassHeading - compassCourse) % 360) - 180; |
||
509 | break; |
||
1612 | dongfang | 510 | #endif |
1821 | - | 511 | case 't': // motor test |
512 | if (RxDataLen > 20) { |
||
513 | memcpy(&motorTest[0], (uint8_t*) pRxData, sizeof(motorTest)); |
||
514 | } else { |
||
515 | memcpy(&motorTest[0], (uint8_t*) pRxData, 4); |
||
516 | } |
||
517 | motorTestActive = 255; |
||
518 | externalControlActive = 255; |
||
519 | break; |
||
1612 | dongfang | 520 | |
1821 | - | 521 | case 'n':// "Get Mixer Table |
522 | while (!txd_complete) |
||
523 | ; // wait for previous frame to be sent |
||
1960 | - | 524 | SendOutData('N', FC_ADDRESS, 1, (uint8_t *) &mixerMatrix, sizeof(mixerMatrix)); |
1821 | - | 525 | break; |
1612 | dongfang | 526 | |
1821 | - | 527 | case 'm':// "Set Mixer Table |
528 | if (pRxData[0] == EEMIXER_REVISION) { |
||
1960 | - | 529 | memcpy(&mixerMatrix, (uint8_t*) pRxData, sizeof(mixerMatrix)); |
530 | mixerMatrix_writeToEEProm(); |
||
1821 | - | 531 | while (!txd_complete) |
532 | ; // wait for previous frame to be sent |
||
533 | tempchar1 = 1; |
||
534 | } else { |
||
535 | tempchar1 = 0; |
||
536 | } |
||
537 | SendOutData('M', FC_ADDRESS, 1, &tempchar1, 1); |
||
538 | break; |
||
1612 | dongfang | 539 | |
1821 | - | 540 | case 'p': // get PPM channels |
541 | request_PPMChannels = TRUE; |
||
542 | break; |
||
1612 | dongfang | 543 | |
1821 | - | 544 | case 'q':// request settings |
545 | if (pRxData[0] == 0xFF) { |
||
1960 | - | 546 | pRxData[0] = getParamByte(PID_ACTIVE_SET); |
1821 | - | 547 | } |
548 | // limit settings range |
||
549 | if (pRxData[0] < 1) |
||
550 | pRxData[0] = 1; // limit to 1 |
||
551 | else if (pRxData[0] > 5) |
||
552 | pRxData[0] = 5; // limit to 5 |
||
553 | // load requested parameter set |
||
1960 | - | 554 | paramSet_readFromEEProm(pRxData[0]); |
1821 | - | 555 | tempchar1 = pRxData[0]; |
556 | tempchar2 = EEPARAM_REVISION; |
||
557 | while (!txd_complete) |
||
558 | ; // wait for previous frame to be sent |
||
559 | SendOutData('Q', FC_ADDRESS, 3, &tempchar1, sizeof(tempchar1), |
||
560 | &tempchar2, sizeof(tempchar2), (uint8_t *) &staticParams, |
||
561 | sizeof(staticParams)); |
||
562 | break; |
||
1612 | dongfang | 563 | |
1821 | - | 564 | case 's': // save settings |
565 | if (!(MKFlags & MKFLAG_MOTOR_RUN)) // save settings only if motors are off |
||
566 | { |
||
567 | if ((1 <= pRxData[0]) && (pRxData[0] <= 5) && (pRxData[1] |
||
568 | == EEPARAM_REVISION)) // check for setting to be in range and version of settings |
||
569 | { |
||
570 | memcpy(&staticParams, (uint8_t*) &pRxData[2], sizeof(staticParams)); |
||
1960 | - | 571 | paramSet_writeToEEProm(pRxData[0]); |
1821 | - | 572 | tempchar1 = getActiveParamSet(); |
573 | beepNumber(tempchar1); |
||
574 | } else { |
||
575 | tempchar1 = 0; //indicate bad data |
||
576 | } |
||
577 | while (!txd_complete) |
||
578 | ; // wait for previous frame to be sent |
||
579 | SendOutData('S', FC_ADDRESS, 1, &tempchar1, sizeof(tempchar1)); |
||
580 | } |
||
581 | break; |
||
1612 | dongfang | 582 | |
1821 | - | 583 | default: |
584 | //unsupported command received |
||
585 | break; |
||
586 | } // case FC_ADDRESS: |
||
1612 | dongfang | 587 | |
1821 | - | 588 | default: // any Slave Address |
589 | switch (rxd_buffer[2]) { |
||
590 | case 'a':// request for labels of the analog debug outputs |
||
591 | request_DebugLabel = pRxData[0]; |
||
592 | if (request_DebugLabel > 31) |
||
593 | request_DebugLabel = 31; |
||
594 | externalControlActive = 255; |
||
595 | break; |
||
1612 | dongfang | 596 | |
1821 | - | 597 | case 'b': // submit extern control |
598 | memcpy(&externalControl, (uint8_t*) pRxData, sizeof(externalControl)); |
||
599 | ConfirmFrame = externalControl.frame; |
||
600 | externalControlActive = 255; |
||
601 | break; |
||
1612 | dongfang | 602 | |
1821 | - | 603 | case 'h':// request for display columns |
604 | externalControlActive = 255; |
||
605 | RemoteKeys |= pRxData[0]; |
||
606 | if (RemoteKeys) |
||
607 | DisplayLine = 0; |
||
608 | request_Display = TRUE; |
||
609 | break; |
||
1612 | dongfang | 610 | |
1821 | - | 611 | case 'l':// request for display columns |
612 | externalControlActive = 255; |
||
613 | MenuItem = pRxData[0]; |
||
614 | request_Display1 = TRUE; |
||
615 | break; |
||
1612 | dongfang | 616 | |
1821 | - | 617 | case 'v': // request for version and board release |
618 | request_VerInfo = TRUE; |
||
619 | break; |
||
1775 | - | 620 | |
1821 | - | 621 | case 'x': |
622 | request_variables = TRUE; |
||
623 | break; |
||
1612 | dongfang | 624 | |
1821 | - | 625 | case 'g':// get external control data |
626 | request_ExternalControl = TRUE; |
||
627 | break; |
||
1612 | dongfang | 628 | |
1821 | - | 629 | case 'd': // request for the debug data |
630 | DebugData_Interval = (uint16_t) pRxData[0] * 10; |
||
631 | if (DebugData_Interval > 0) |
||
632 | request_DebugData = TRUE; |
||
633 | break; |
||
1612 | dongfang | 634 | |
1821 | - | 635 | case 'c': // request for the 3D data |
636 | Data3D_Interval = (uint16_t) pRxData[0] * 10; |
||
637 | if (Data3D_Interval > 0) |
||
638 | request_Data3D = TRUE; |
||
639 | break; |
||
640 | |||
641 | default: |
||
642 | //unsupported command received |
||
643 | break; |
||
644 | } |
||
645 | break; // default: |
||
646 | } |
||
647 | // unlock the rxd buffer after processing |
||
648 | pRxData = 0; |
||
649 | RxDataLen = 0; |
||
650 | rxd_buffer_locked = FALSE; |
||
1612 | dongfang | 651 | } |
652 | |||
1645 | - | 653 | /************************************************************************/ |
654 | /* Routine für die Serielle Ausgabe */ |
||
655 | /************************************************************************/ |
||
1821 | - | 656 | int16_t uart_putchar(int8_t c) { |
657 | if (c == '\n') |
||
658 | uart_putchar('\r'); |
||
659 | // wait until previous character was send |
||
660 | loop_until_bit_is_set(UCSR0A, UDRE0); |
||
661 | // send character |
||
662 | UDR0 = c; |
||
663 | return (0); |
||
1612 | dongfang | 664 | } |
665 | |||
666 | //--------------------------------------------------------------------------------------------- |
||
1645 | - | 667 | void usart0_TransmitTxData(void) { |
1821 | - | 668 | if (!txd_complete) |
669 | return; |
||
1612 | dongfang | 670 | |
1821 | - | 671 | if (request_VerInfo && txd_complete) { |
672 | SendOutData('V', FC_ADDRESS, 1, (uint8_t *) &UART_VersionInfo, |
||
673 | sizeof(UART_VersionInfo)); |
||
674 | request_VerInfo = FALSE; |
||
675 | } |
||
1612 | dongfang | 676 | |
1821 | - | 677 | if (request_Display && txd_complete) { |
678 | LCD_PrintMenu(); |
||
679 | SendOutData('H', FC_ADDRESS, 2, &DisplayLine, sizeof(DisplayLine), |
||
680 | &DisplayBuff[DisplayLine * 20], 20); |
||
681 | DisplayLine++; |
||
682 | if (DisplayLine >= 4) |
||
683 | DisplayLine = 0; |
||
684 | request_Display = FALSE; |
||
685 | } |
||
1612 | dongfang | 686 | |
1821 | - | 687 | if (request_Display1 && txd_complete) { |
688 | LCD_PrintMenu(); |
||
689 | SendOutData('L', FC_ADDRESS, 3, &MenuItem, sizeof(MenuItem), &MaxMenuItem, |
||
690 | sizeof(MaxMenuItem), DisplayBuff, sizeof(DisplayBuff)); |
||
691 | request_Display1 = FALSE; |
||
692 | } |
||
693 | |||
694 | if (request_DebugLabel != 0xFF) { // Texte für die Analogdaten |
||
695 | uint8_t label[16]; // local sram buffer |
||
696 | memcpy_P(label, ANALOG_LABEL[request_DebugLabel], 16); // read lable from flash to sram buffer |
||
697 | SendOutData('A', FC_ADDRESS, 2, (uint8_t *) &request_DebugLabel, |
||
698 | sizeof(request_DebugLabel), label, 16); |
||
699 | request_DebugLabel = 0xFF; |
||
700 | } |
||
701 | |||
702 | if (ConfirmFrame && txd_complete) { // Datensatz ohne CRC bestätigen |
||
703 | SendOutData('B', FC_ADDRESS, 1, (uint8_t*) &ConfirmFrame, |
||
704 | sizeof(ConfirmFrame)); |
||
705 | ConfirmFrame = 0; |
||
706 | } |
||
707 | |||
1887 | - | 708 | if (((DebugData_Interval && checkDelay(DebugData_Timer)) || request_DebugData) |
1821 | - | 709 | && txd_complete) { |
1955 | - | 710 | SendOutData('D', FC_ADDRESS, 1, (uint8_t *) &debugOut, sizeof(debugOut)); |
1887 | - | 711 | DebugData_Timer = setDelay(DebugData_Interval); |
1821 | - | 712 | request_DebugData = FALSE; |
713 | } |
||
714 | |||
1887 | - | 715 | if (((Data3D_Interval && checkDelay(Data3D_Timer)) || request_Data3D) |
1821 | - | 716 | && txd_complete) { |
717 | SendOutData('C', FC_ADDRESS, 1, (uint8_t *) &Data3D, sizeof(Data3D)); |
||
718 | Data3D.AngleNick = (int16_t) ((10 * angle[PITCH]) |
||
719 | / GYRO_DEG_FACTOR_PITCHROLL); // convert to multiple of 0.1° |
||
720 | Data3D.AngleRoll = (int16_t) ((10 * angle[ROLL]) |
||
721 | / GYRO_DEG_FACTOR_PITCHROLL); // convert to multiple of 0.1° |
||
722 | Data3D.Heading = (int16_t) ((10 * yawGyroHeading) / GYRO_DEG_FACTOR_YAW); // convert to multiple of 0.1° |
||
1887 | - | 723 | Data3D_Timer = setDelay(Data3D_Interval); |
1821 | - | 724 | request_Data3D = FALSE; |
725 | } |
||
726 | |||
727 | if (request_ExternalControl && txd_complete) { |
||
728 | SendOutData('G', FC_ADDRESS, 1, (uint8_t *) &externalControl, |
||
729 | sizeof(externalControl)); |
||
730 | request_ExternalControl = FALSE; |
||
731 | } |
||
732 | |||
1612 | dongfang | 733 | #ifdef USE_MK3MAG |
1887 | - | 734 | if((checkDelay(Compass_Timer)) && txd_complete) { |
1821 | - | 735 | ToMk3Mag.Attitude[0] = (int16_t)((10 * angle[PITCH]) / GYRO_DEG_FACTOR_PITCHROLL); // approx. 0.1 deg |
736 | ToMk3Mag.Attitude[1] = (int16_t)((10 * angle[ROLL]) / GYRO_DEG_FACTOR_PITCHROLL); // approx. 0.1 deg |
||
1960 | - | 737 | ToMk3Mag.UserParam[0] = dynamicParams.userParams[0]; |
738 | ToMk3Mag.UserParam[1] = dynamicParams.userParams[1]; |
||
1821 | - | 739 | ToMk3Mag.CalState = compassCalState; |
740 | SendOutData('w', MK3MAG_ADDRESS, 1,(uint8_t *) &ToMk3Mag,sizeof(ToMk3Mag)); |
||
741 | // the last state is 5 and should be send only once to avoid multiple flash writing |
||
742 | if(compassCalState > 4) compassCalState = 0; |
||
1887 | - | 743 | Compass_Timer = setDelay(99); |
1821 | - | 744 | } |
1612 | dongfang | 745 | #endif |
746 | |||
1821 | - | 747 | if (request_MotorTest && txd_complete) { |
748 | SendOutData('T', FC_ADDRESS, 0); |
||
749 | request_MotorTest = FALSE; |
||
750 | } |
||
1775 | - | 751 | |
1821 | - | 752 | if (request_PPMChannels && txd_complete) { |
753 | SendOutData('P', FC_ADDRESS, 1, (uint8_t *) &PPM_in, sizeof(PPM_in)); |
||
754 | request_PPMChannels = FALSE; |
||
755 | } |
||
756 | |||
757 | if (request_variables && txd_complete) { |
||
758 | SendOutData('X', FC_ADDRESS, 1, (uint8_t *) &variables, sizeof(variables)); |
||
759 | request_variables = FALSE; |
||
760 | } |
||
1612 | dongfang | 761 | } |