Rev 2018 | Rev 2026 | 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 |
||
2018 | - | 3 | // + Nur für den privaten Gebrauch |
1612 | dongfang | 4 | // + www.MikroKopter.com |
5 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
2018 | - | 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. |
||
2018 | - | 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 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
2018 | - | 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 |
||
2018 | - | 17 | // + auf anderen Webseiten oder Medien verüffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de" |
1623 | - | 18 | // + eindeutig als Ursprung verlinkt und genannt werden |
1612 | dongfang | 19 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
2018 | - | 20 | // + Keine Gewühr auf Fehlerfreiheit, Vollstündigkeit oder Funktion |
1612 | dongfang | 21 | // + Benutzung auf eigene Gefahr |
2018 | - | 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 |
||
2018 | - | 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 | |
69 | #ifdef USE_MK3MAG |
||
70 | #include "mk3mag.h" |
||
71 | #endif |
||
72 | |||
73 | #define FC_ADDRESS 1 |
||
74 | #define NC_ADDRESS 2 |
||
75 | #define MK3MAG_ADDRESS 3 |
||
76 | |||
77 | #define FALSE 0 |
||
78 | #define TRUE 1 |
||
79 | //int8_t test __attribute__ ((section (".noinit"))); |
||
2018 | - | 80 | uint8_t request_verInfo = FALSE; |
81 | uint8_t request_externalControl = FALSE; |
||
82 | uint8_t request_display = FALSE; |
||
83 | uint8_t request_display1 = FALSE; |
||
84 | uint8_t request_debugData = FALSE; |
||
85 | uint8_t request_data3D = FALSE; |
||
86 | uint8_t request_debugLabel = 255; |
||
1821 | - | 87 | uint8_t request_PPMChannels = FALSE; |
2018 | - | 88 | uint8_t request_motorTest = FALSE; |
1821 | - | 89 | uint8_t request_variables = FALSE; |
1775 | - | 90 | |
2018 | - | 91 | uint8_t displayLine = 0; |
1612 | dongfang | 92 | |
93 | volatile uint8_t txd_buffer[TXD_BUFFER_LEN]; |
||
94 | volatile uint8_t rxd_buffer_locked = FALSE; |
||
95 | volatile uint8_t rxd_buffer[RXD_BUFFER_LEN]; |
||
96 | volatile uint8_t txd_complete = TRUE; |
||
2018 | - | 97 | volatile uint8_t receivedBytes = 0; |
1612 | dongfang | 98 | volatile uint8_t *pRxData = 0; |
2018 | - | 99 | volatile uint8_t rxDataLen = 0; |
1612 | dongfang | 100 | |
1821 | - | 101 | uint8_t motorTestActive = 0; |
102 | uint8_t motorTest[16] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; |
||
2018 | - | 103 | uint8_t confirmFrame; |
1612 | dongfang | 104 | |
105 | typedef struct { |
||
1821 | - | 106 | int16_t Heading; |
107 | }__attribute__((packed)) Heading_t; |
||
1612 | dongfang | 108 | |
1955 | - | 109 | DebugOut_t debugOut; |
2018 | - | 110 | Data3D_t data3D; |
1612 | dongfang | 111 | |
2018 | - | 112 | uint16_t debugData_timer; |
113 | uint16_t data3D_timer; |
||
114 | uint16_t debugData_interval = 0; // in 1ms |
||
115 | uint16_t data3D_interval = 0; // in 1ms |
||
1612 | dongfang | 116 | |
117 | #ifdef USE_MK3MAG |
||
2018 | - | 118 | int16_t compass_timer; |
1612 | dongfang | 119 | #endif |
120 | |||
121 | // keep lables in flash to save 512 bytes of sram space |
||
122 | const prog_uint8_t ANALOG_LABEL[32][16] = { |
||
1821 | - | 123 | //1234567890123456 |
124 | "AnglePitch ", //0 |
||
125 | "AngleRoll ", |
||
126 | "AngleYaw ", |
||
1974 | - | 127 | "GyroPitch ", |
128 | "GyroRoll ", |
||
129 | "GyroYaw ", //5 |
||
130 | "AccPitch ", |
||
131 | "AccRoll ", |
||
132 | "AccZ ", |
||
1821 | - | 133 | "AccPitch (angle)", |
134 | "AccRoll (angle) ", //10 |
||
1869 | - | 135 | "UBat ", |
1821 | - | 136 | "Pitch Term ", |
137 | "Roll Term ", |
||
1955 | - | 138 | "Yaw Term ", |
1980 | - | 139 | "Throttle Term ", //15 |
1955 | - | 140 | "gyroP ", |
1986 | - | 141 | "ControlAct/10 ", |
142 | "Acc. Vector ", |
||
143 | "Max. Acc. Vector", |
||
144 | "var0 ", //20 |
||
2019 | - | 145 | "rc signal ", |
1864 | - | 146 | "M1 ", |
147 | "M2 ", |
||
1821 | - | 148 | "M3 ", |
149 | "M4 ", //25 |
||
1864 | - | 150 | "ControlYaw ", |
151 | "Airpress. Range ", |
||
152 | "DriftCompPitch ", |
||
153 | "DriftCompRoll ", |
||
1970 | - | 154 | "Altitude ", //30 |
1821 | - | 155 | "AirpressADC " }; |
1612 | dongfang | 156 | |
157 | /****************************************************************/ |
||
158 | /* Initialization of the USART0 */ |
||
159 | /****************************************************************/ |
||
2018 | - | 160 | void usart0_init(void) { |
1821 | - | 161 | uint8_t sreg = SREG; |
162 | uint16_t ubrr = (uint16_t) ((uint32_t) SYSCLK / (8 * USART0_BAUD) - 1); |
||
163 | |||
164 | // disable all interrupts before configuration |
||
165 | cli(); |
||
166 | |||
167 | // disable RX-Interrupt |
||
168 | UCSR0B &= ~(1 << RXCIE0); |
||
169 | // disable TX-Interrupt |
||
170 | UCSR0B &= ~(1 << TXCIE0); |
||
171 | |||
172 | // set direction of RXD0 and TXD0 pins |
||
173 | // set RXD0 (PD0) as an input pin |
||
174 | PORTD |= (1 << PORTD0); |
||
175 | DDRD &= ~(1 << DDD0); |
||
176 | // set TXD0 (PD1) as an output pin |
||
177 | PORTD |= (1 << PORTD1); |
||
178 | DDRD |= (1 << DDD1); |
||
179 | |||
180 | // USART0 Baud Rate Register |
||
181 | // set clock divider |
||
182 | UBRR0H = (uint8_t) (ubrr >> 8); |
||
183 | UBRR0L = (uint8_t) ubrr; |
||
184 | |||
185 | // USART0 Control and Status Register A, B, C |
||
186 | |||
187 | // enable double speed operation in |
||
188 | UCSR0A |= (1 << U2X0); |
||
189 | // enable receiver and transmitter in |
||
190 | UCSR0B = (1 << TXEN0) | (1 << RXEN0); |
||
191 | // set asynchronous mode |
||
192 | UCSR0C &= ~(1 << UMSEL01); |
||
193 | UCSR0C &= ~(1 << UMSEL00); |
||
194 | // no parity |
||
195 | UCSR0C &= ~(1 << UPM01); |
||
196 | UCSR0C &= ~(1 << UPM00); |
||
197 | // 1 stop bit |
||
198 | UCSR0C &= ~(1 << USBS0); |
||
199 | // 8-bit |
||
200 | UCSR0B &= ~(1 << UCSZ02); |
||
201 | UCSR0C |= (1 << UCSZ01); |
||
202 | UCSR0C |= (1 << UCSZ00); |
||
203 | |||
204 | // flush receive buffer |
||
205 | while (UCSR0A & (1 << RXC0)) |
||
206 | UDR0; |
||
207 | |||
208 | // enable interrupts at the end |
||
209 | // enable RX-Interrupt |
||
210 | UCSR0B |= (1 << RXCIE0); |
||
211 | // enable TX-Interrupt |
||
212 | UCSR0B |= (1 << TXCIE0); |
||
213 | |||
214 | // initialize the debug timer |
||
2018 | - | 215 | debugData_timer = setDelay(debugData_interval); |
1821 | - | 216 | |
217 | // unlock rxd_buffer |
||
218 | rxd_buffer_locked = FALSE; |
||
219 | pRxData = 0; |
||
2018 | - | 220 | rxDataLen = 0; |
1821 | - | 221 | |
222 | // no bytes to send |
||
223 | txd_complete = TRUE; |
||
224 | |||
1612 | dongfang | 225 | #ifdef USE_MK3MAG |
2018 | - | 226 | compass_timer = setDelay(220); |
1612 | dongfang | 227 | #endif |
1821 | - | 228 | |
2018 | - | 229 | versionInfo.SWMajor = VERSION_MAJOR; |
230 | versionInfo.SWMinor = VERSION_MINOR; |
||
231 | versionInfo.SWPatch = VERSION_PATCH; |
||
232 | versionInfo.protoMajor = VERSION_SERIAL_MAJOR; |
||
233 | versionInfo.protoMinor = VERSION_SERIAL_MINOR; |
||
1821 | - | 234 | |
235 | // restore global interrupt flags |
||
236 | SREG = sreg; |
||
1612 | dongfang | 237 | } |
238 | |||
239 | /****************************************************************/ |
||
240 | /* USART0 transmitter ISR */ |
||
241 | /****************************************************************/ |
||
2018 | - | 242 | ISR(USART0_TX_vect) { |
1821 | - | 243 | static uint16_t ptr_txd_buffer = 0; |
244 | uint8_t tmp_tx; |
||
245 | if (!txd_complete) { // transmission not completed |
||
246 | ptr_txd_buffer++; // die [0] wurde schon gesendet |
||
247 | tmp_tx = txd_buffer[ptr_txd_buffer]; |
||
248 | // if terminating character or end of txd buffer was reached |
||
249 | if ((tmp_tx == '\r') || (ptr_txd_buffer == TXD_BUFFER_LEN)) { |
||
250 | ptr_txd_buffer = 0; // reset txd pointer |
||
251 | txd_complete = 1; // stop transmission |
||
252 | } |
||
253 | UDR0 = tmp_tx; // send current byte will trigger this ISR again |
||
254 | } |
||
255 | // transmission completed |
||
256 | else |
||
257 | ptr_txd_buffer = 0; |
||
1612 | dongfang | 258 | } |
259 | |||
260 | /****************************************************************/ |
||
261 | /* USART0 receiver ISR */ |
||
262 | /****************************************************************/ |
||
2018 | - | 263 | ISR(USART0_RX_vect) { |
1969 | - | 264 | static uint16_t checksum; |
1821 | - | 265 | static uint8_t ptr_rxd_buffer = 0; |
1969 | - | 266 | uint8_t checksum1, checksum2; |
1821 | - | 267 | uint8_t c; |
1612 | dongfang | 268 | |
1821 | - | 269 | c = UDR0; // catch the received byte |
1612 | dongfang | 270 | |
1821 | - | 271 | if (rxd_buffer_locked) |
272 | return; // if rxd buffer is locked immediately return |
||
1612 | dongfang | 273 | |
1821 | - | 274 | // the rxd buffer is unlocked |
275 | if ((ptr_rxd_buffer == 0) && (c == '#')) { // if rxd buffer is empty and syncronisation character is received |
||
276 | rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer |
||
1969 | - | 277 | checksum = c; // init checksum |
1821 | - | 278 | } |
1612 | dongfang | 279 | #if 0 |
1821 | - | 280 | else if (ptr_rxd_buffer == 1) { // handle address |
281 | rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer |
||
1969 | - | 282 | checksum += c; // update checksum |
1821 | - | 283 | } |
1612 | dongfang | 284 | #endif |
1821 | - | 285 | else if (ptr_rxd_buffer < RXD_BUFFER_LEN) { // collect incomming bytes |
286 | if (c != '\r') { // no termination character |
||
287 | rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer |
||
1969 | - | 288 | checksum += c; // update checksum |
1821 | - | 289 | } else { // termination character was received |
290 | // the last 2 bytes are no subject for checksum calculation |
||
291 | // they are the checksum itself |
||
1969 | - | 292 | checksum -= rxd_buffer[ptr_rxd_buffer - 2]; |
293 | checksum -= rxd_buffer[ptr_rxd_buffer - 1]; |
||
1821 | - | 294 | // calculate checksum from transmitted data |
1969 | - | 295 | checksum %= 4096; |
296 | checksum1 = '=' + checksum / 64; |
||
297 | checksum2 = '=' + checksum % 64; |
||
1821 | - | 298 | // compare checksum to transmitted checksum bytes |
1969 | - | 299 | if ((checksum1 == rxd_buffer[ptr_rxd_buffer - 2]) && (checksum2 |
1821 | - | 300 | == rxd_buffer[ptr_rxd_buffer - 1])) { |
301 | // checksum valid |
||
302 | rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character |
||
2018 | - | 303 | receivedBytes = ptr_rxd_buffer + 1;// store number of received bytes |
1821 | - | 304 | rxd_buffer_locked = TRUE; // lock the rxd buffer |
305 | // if 2nd byte is an 'R' enable watchdog that will result in an reset |
||
306 | if (rxd_buffer[2] == 'R') { |
||
307 | wdt_enable(WDTO_250MS); |
||
308 | } // Reset-Commando |
||
309 | } else { // checksum invalid |
||
310 | rxd_buffer_locked = FALSE; // unlock rxd buffer |
||
311 | } |
||
312 | ptr_rxd_buffer = 0; // reset rxd buffer pointer |
||
313 | } |
||
314 | } else { // rxd buffer overrun |
||
315 | ptr_rxd_buffer = 0; // reset rxd buffer |
||
316 | rxd_buffer_locked = FALSE; // unlock rxd buffer |
||
317 | } |
||
1612 | dongfang | 318 | } |
319 | |||
320 | // -------------------------------------------------------------------------- |
||
1969 | - | 321 | void Addchecksum(uint16_t datalen) { |
322 | uint16_t tmpchecksum = 0, i; |
||
1821 | - | 323 | for (i = 0; i < datalen; i++) { |
1969 | - | 324 | tmpchecksum += txd_buffer[i]; |
1821 | - | 325 | } |
1969 | - | 326 | tmpchecksum %= 4096; |
327 | txd_buffer[i++] = '=' + tmpchecksum / 64; |
||
328 | txd_buffer[i++] = '=' + tmpchecksum % 64; |
||
1821 | - | 329 | txd_buffer[i++] = '\r'; |
330 | txd_complete = FALSE; |
||
331 | UDR0 = txd_buffer[0]; // initiates the transmittion (continued in the TXD ISR) |
||
1612 | dongfang | 332 | } |
333 | |||
334 | // -------------------------------------------------------------------------- |
||
1775 | - | 335 | // application example: |
2018 | - | 336 | // sendOutData('A', FC_ADDRESS, 2, (uint8_t *)&request_DebugLabel, sizeof(request_DebugLabel), label, 16); |
1775 | - | 337 | /* |
2018 | - | 338 | void sendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) { // uint8_t *pdata, uint8_t len, ... |
1821 | - | 339 | va_list ap; |
340 | uint16_t txd_bufferIndex = 0; |
||
341 | uint8_t *currentBuffer; |
||
342 | uint8_t currentBufferIndex; |
||
343 | uint16_t lengthOfCurrentBuffer; |
||
344 | uint8_t shift = 0; |
||
1775 | - | 345 | |
1821 | - | 346 | txd_buffer[txd_bufferIndex++] = '#'; // Start character |
347 | txd_buffer[txd_bufferIndex++] = 'a' + addr; // Address (a=0; b=1,...) |
||
348 | txd_buffer[txd_bufferIndex++] = cmd; // Command |
||
1775 | - | 349 | |
1821 | - | 350 | va_start(ap, numofbuffers); |
351 | |||
352 | while(numofbuffers) { |
||
353 | currentBuffer = va_arg(ap, uint8_t*); |
||
354 | lengthOfCurrentBuffer = va_arg(ap, int); |
||
355 | currentBufferIndex = 0; |
||
356 | // Encode data: 3 bytes of data are encoded into 4 bytes, |
||
357 | // where the 2 most significant bits are both 0. |
||
358 | while(currentBufferIndex != lengthOfCurrentBuffer) { |
||
359 | if (!shift) txd_buffer[txd_bufferIndex] = 0; |
||
360 | txd_buffer[txd_bufferIndex] |= currentBuffer[currentBufferIndex] >> (shift + 2); |
||
361 | txd_buffer[++txd_bufferIndex] = (currentBuffer[currentBufferIndex] << (4 - shift)) & 0b00111111; |
||
362 | shift += 2; |
||
363 | if (shift == 6) { shift=0; txd_bufferIndex++; } |
||
364 | currentBufferIndex++; |
||
365 | } |
||
366 | } |
||
367 | // If the number of data bytes was not divisible by 3, stuff |
||
368 | // with 0 pseudodata until length is again divisible by 3. |
||
369 | if (shift == 2) { |
||
370 | // We need to stuff with zero bytes at the end. |
||
371 | txd_buffer[txd_bufferIndex] &= 0b00110000; |
||
372 | txd_buffer[++txd_bufferIndex] = 0; |
||
373 | shift = 4; |
||
374 | } |
||
375 | if (shift == 4) { |
||
376 | // We need to stuff with zero bytes at the end. |
||
377 | txd_buffer[txd_bufferIndex++] &= 0b00111100; |
||
378 | txd_buffer[txd_bufferIndex] = 0; |
||
379 | } |
||
380 | va_end(ap); |
||
1969 | - | 381 | Addchecksum(pt); // add checksum after data block and initates the transmission |
1821 | - | 382 | } |
383 | */ |
||
384 | |||
2018 | - | 385 | void sendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) { // uint8_t *pdata, uint8_t len, ... |
1821 | - | 386 | va_list ap; |
387 | uint16_t pt = 0; |
||
388 | uint8_t a, b, c; |
||
389 | uint8_t ptr = 0; |
||
1612 | dongfang | 390 | |
1821 | - | 391 | uint8_t *pdata = 0; |
392 | int len = 0; |
||
1612 | dongfang | 393 | |
1821 | - | 394 | txd_buffer[pt++] = '#'; // Start character |
395 | txd_buffer[pt++] = 'a' + addr; // Address (a=0; b=1,...) |
||
396 | txd_buffer[pt++] = cmd; // Command |
||
397 | |||
398 | va_start(ap, numofbuffers); |
||
399 | |||
400 | if (numofbuffers) { |
||
401 | pdata = va_arg(ap, uint8_t*); |
||
402 | len = va_arg(ap, int); |
||
403 | ptr = 0; |
||
404 | numofbuffers--; |
||
405 | } |
||
406 | |||
407 | while (len) { |
||
408 | if (len) { |
||
409 | a = pdata[ptr++]; |
||
410 | len--; |
||
411 | if ((!len) && numofbuffers) { |
||
412 | pdata = va_arg(ap, uint8_t*); |
||
413 | len = va_arg(ap, int); |
||
414 | ptr = 0; |
||
415 | numofbuffers--; |
||
416 | } |
||
417 | } else |
||
418 | a = 0; |
||
419 | if (len) { |
||
420 | b = pdata[ptr++]; |
||
421 | len--; |
||
422 | if ((!len) && numofbuffers) { |
||
423 | pdata = va_arg(ap, uint8_t*); |
||
424 | len = va_arg(ap, int); |
||
425 | ptr = 0; |
||
426 | numofbuffers--; |
||
427 | } |
||
428 | } else |
||
429 | b = 0; |
||
430 | if (len) { |
||
431 | c = pdata[ptr++]; |
||
432 | len--; |
||
433 | if ((!len) && numofbuffers) { |
||
434 | pdata = va_arg(ap, uint8_t*); |
||
435 | len = va_arg(ap, int); |
||
436 | ptr = 0; |
||
437 | numofbuffers--; |
||
438 | } |
||
439 | } else |
||
440 | c = 0; |
||
441 | txd_buffer[pt++] = '=' + (a >> 2); |
||
442 | txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4)); |
||
443 | txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6)); |
||
444 | txd_buffer[pt++] = '=' + (c & 0x3f); |
||
445 | } |
||
446 | va_end(ap); |
||
1969 | - | 447 | Addchecksum(pt); // add checksum after data block and initates the transmission |
1612 | dongfang | 448 | } |
449 | |||
450 | // -------------------------------------------------------------------------- |
||
451 | void Decode64(void) { |
||
1821 | - | 452 | uint8_t a, b, c, d; |
453 | uint8_t x, y, z; |
||
454 | uint8_t ptrIn = 3; |
||
455 | uint8_t ptrOut = 3; |
||
2018 | - | 456 | uint8_t len = receivedBytes - 6; |
1821 | - | 457 | |
458 | while (len) { |
||
459 | a = rxd_buffer[ptrIn++] - '='; |
||
460 | b = rxd_buffer[ptrIn++] - '='; |
||
461 | c = rxd_buffer[ptrIn++] - '='; |
||
462 | d = rxd_buffer[ptrIn++] - '='; |
||
463 | //if(ptrIn > ReceivedBytes - 3) break; |
||
464 | |||
465 | x = (a << 2) | (b >> 4); |
||
466 | y = ((b & 0x0f) << 4) | (c >> 2); |
||
467 | z = ((c & 0x03) << 6) | d; |
||
468 | |||
469 | if (len--) |
||
470 | rxd_buffer[ptrOut++] = x; |
||
471 | else |
||
472 | break; |
||
473 | if (len--) |
||
474 | rxd_buffer[ptrOut++] = y; |
||
475 | else |
||
476 | break; |
||
477 | if (len--) |
||
478 | rxd_buffer[ptrOut++] = z; |
||
479 | else |
||
480 | break; |
||
481 | } |
||
482 | pRxData = &rxd_buffer[3]; |
||
2018 | - | 483 | rxDataLen = ptrOut - 3; |
1612 | dongfang | 484 | } |
485 | |||
486 | // -------------------------------------------------------------------------- |
||
2018 | - | 487 | void usart0_processRxData(void) { |
1821 | - | 488 | // We control the motorTestActive var from here: Count it down. |
489 | if (motorTestActive) |
||
490 | motorTestActive--; |
||
491 | // if data in the rxd buffer are not locked immediately return |
||
492 | if (!rxd_buffer_locked) |
||
493 | return; |
||
1980 | - | 494 | uint8_t tempchar[3]; |
1821 | - | 495 | Decode64(); // decode data block in rxd_buffer |
1775 | - | 496 | |
1821 | - | 497 | switch (rxd_buffer[1] - 'a') { |
1775 | - | 498 | |
1821 | - | 499 | case FC_ADDRESS: |
500 | switch (rxd_buffer[2]) { |
||
1612 | dongfang | 501 | #ifdef USE_MK3MAG |
1821 | - | 502 | case 'K':// compass value |
503 | compassHeading = ((Heading_t *)pRxData)->Heading; |
||
504 | // compassOffCourse = ((540 + compassHeading - compassCourse) % 360) - 180; |
||
505 | break; |
||
1612 | dongfang | 506 | #endif |
1821 | - | 507 | case 't': // motor test |
2018 | - | 508 | if (rxDataLen > 20) { |
1821 | - | 509 | memcpy(&motorTest[0], (uint8_t*) pRxData, sizeof(motorTest)); |
510 | } else { |
||
511 | memcpy(&motorTest[0], (uint8_t*) pRxData, 4); |
||
512 | } |
||
513 | motorTestActive = 255; |
||
514 | externalControlActive = 255; |
||
515 | break; |
||
1612 | dongfang | 516 | |
1821 | - | 517 | case 'n':// "Get Mixer Table |
518 | while (!txd_complete) |
||
519 | ; // wait for previous frame to be sent |
||
2018 | - | 520 | sendOutData('N', FC_ADDRESS, 1, (uint8_t *) &mixerMatrix, sizeof(mixerMatrix)); |
1821 | - | 521 | break; |
1612 | dongfang | 522 | |
1821 | - | 523 | case 'm':// "Set Mixer Table |
524 | if (pRxData[0] == EEMIXER_REVISION) { |
||
1960 | - | 525 | memcpy(&mixerMatrix, (uint8_t*) pRxData, sizeof(mixerMatrix)); |
526 | mixerMatrix_writeToEEProm(); |
||
1821 | - | 527 | while (!txd_complete) |
528 | ; // wait for previous frame to be sent |
||
1980 | - | 529 | tempchar[0] = 1; |
1821 | - | 530 | } else { |
1980 | - | 531 | tempchar[0] = 0; |
1821 | - | 532 | } |
2018 | - | 533 | sendOutData('M', FC_ADDRESS, 1, &tempchar, 1); |
1821 | - | 534 | break; |
1612 | dongfang | 535 | |
1821 | - | 536 | case 'p': // get PPM channels |
537 | request_PPMChannels = TRUE; |
||
538 | break; |
||
1612 | dongfang | 539 | |
1821 | - | 540 | case 'q':// request settings |
541 | if (pRxData[0] == 0xFF) { |
||
1960 | - | 542 | pRxData[0] = getParamByte(PID_ACTIVE_SET); |
1821 | - | 543 | } |
544 | // limit settings range |
||
545 | if (pRxData[0] < 1) |
||
546 | pRxData[0] = 1; // limit to 1 |
||
547 | else if (pRxData[0] > 5) |
||
548 | pRxData[0] = 5; // limit to 5 |
||
549 | // load requested parameter set |
||
1960 | - | 550 | paramSet_readFromEEProm(pRxData[0]); |
1980 | - | 551 | tempchar[0] = pRxData[0]; |
552 | tempchar[1] = EEPARAM_REVISION; |
||
553 | tempchar[2] = sizeof(staticParams); |
||
1821 | - | 554 | while (!txd_complete) |
555 | ; // wait for previous frame to be sent |
||
2018 | - | 556 | sendOutData('Q', FC_ADDRESS, 2, &tempchar, 3, (uint8_t *) &staticParams, sizeof(staticParams)); |
1821 | - | 557 | break; |
1612 | dongfang | 558 | |
1821 | - | 559 | case 's': // save settings |
560 | if (!(MKFlags & MKFLAG_MOTOR_RUN)) // save settings only if motors are off |
||
561 | { |
||
562 | if ((1 <= pRxData[0]) && (pRxData[0] <= 5) && (pRxData[1] |
||
563 | == EEPARAM_REVISION)) // check for setting to be in range and version of settings |
||
564 | { |
||
565 | memcpy(&staticParams, (uint8_t*) &pRxData[2], sizeof(staticParams)); |
||
1960 | - | 566 | paramSet_writeToEEProm(pRxData[0]); |
1980 | - | 567 | tempchar[0] = getActiveParamSet(); |
568 | beepNumber(tempchar[0]); |
||
1821 | - | 569 | } else { |
1980 | - | 570 | tempchar[0] = 0; //indicate bad data |
1821 | - | 571 | } |
572 | while (!txd_complete) |
||
573 | ; // wait for previous frame to be sent |
||
2018 | - | 574 | sendOutData('S', FC_ADDRESS, 1, &tempchar, 1); |
1821 | - | 575 | } |
576 | break; |
||
1612 | dongfang | 577 | |
1821 | - | 578 | default: |
579 | //unsupported command received |
||
580 | break; |
||
581 | } // case FC_ADDRESS: |
||
1612 | dongfang | 582 | |
1821 | - | 583 | default: // any Slave Address |
584 | switch (rxd_buffer[2]) { |
||
585 | case 'a':// request for labels of the analog debug outputs |
||
2018 | - | 586 | request_debugLabel = pRxData[0]; |
587 | if (request_debugLabel > 31) |
||
588 | request_debugLabel = 31; |
||
1821 | - | 589 | break; |
1612 | dongfang | 590 | |
1821 | - | 591 | case 'b': // submit extern control |
592 | memcpy(&externalControl, (uint8_t*) pRxData, sizeof(externalControl)); |
||
2018 | - | 593 | confirmFrame = externalControl.frame; |
1821 | - | 594 | externalControlActive = 255; |
595 | break; |
||
1612 | dongfang | 596 | |
1821 | - | 597 | case 'h':// request for display columns |
2018 | - | 598 | remoteKeys |= pRxData[0]; |
599 | if (remoteKeys) |
||
600 | displayLine = 0; |
||
601 | request_display = TRUE; |
||
1821 | - | 602 | break; |
1612 | dongfang | 603 | |
1821 | - | 604 | case 'l':// request for display columns |
2018 | - | 605 | menuItem = pRxData[0]; |
606 | request_display1 = TRUE; |
||
1821 | - | 607 | break; |
1612 | dongfang | 608 | |
1821 | - | 609 | case 'v': // request for version and board release |
2018 | - | 610 | request_verInfo = TRUE; |
1821 | - | 611 | break; |
1775 | - | 612 | |
1821 | - | 613 | case 'x': |
614 | request_variables = TRUE; |
||
615 | break; |
||
1612 | dongfang | 616 | |
1821 | - | 617 | case 'g':// get external control data |
2018 | - | 618 | request_externalControl = TRUE; |
1821 | - | 619 | break; |
1612 | dongfang | 620 | |
1821 | - | 621 | case 'd': // request for the debug data |
2018 | - | 622 | debugData_interval = (uint16_t) pRxData[0] * 10; |
623 | if (debugData_interval > 0) |
||
624 | request_debugData = TRUE; |
||
1821 | - | 625 | break; |
1612 | dongfang | 626 | |
1821 | - | 627 | case 'c': // request for the 3D data |
2018 | - | 628 | data3D_interval = (uint16_t) pRxData[0] * 10; |
629 | if (data3D_interval > 0) |
||
630 | request_data3D = TRUE; |
||
1821 | - | 631 | break; |
632 | |||
633 | default: |
||
634 | //unsupported command received |
||
635 | break; |
||
636 | } |
||
637 | break; // default: |
||
638 | } |
||
639 | // unlock the rxd buffer after processing |
||
640 | pRxData = 0; |
||
2018 | - | 641 | rxDataLen = 0; |
1821 | - | 642 | rxd_buffer_locked = FALSE; |
1612 | dongfang | 643 | } |
644 | |||
1645 | - | 645 | /************************************************************************/ |
2018 | - | 646 | /* Routine für die Serielle Ausgabe */ |
1645 | - | 647 | /************************************************************************/ |
1821 | - | 648 | int16_t uart_putchar(int8_t c) { |
649 | if (c == '\n') |
||
650 | uart_putchar('\r'); |
||
651 | // wait until previous character was send |
||
652 | loop_until_bit_is_set(UCSR0A, UDRE0); |
||
653 | // send character |
||
654 | UDR0 = c; |
||
655 | return (0); |
||
1612 | dongfang | 656 | } |
657 | |||
658 | //--------------------------------------------------------------------------------------------- |
||
2018 | - | 659 | void usart0_transmitTxData(void) { |
1821 | - | 660 | if (!txd_complete) |
661 | return; |
||
1612 | dongfang | 662 | |
2018 | - | 663 | if (request_verInfo && txd_complete) { |
664 | sendOutData('V', FC_ADDRESS, 1, (uint8_t *) &versionInfo, sizeof(versionInfo)); |
||
665 | request_verInfo = FALSE; |
||
1821 | - | 666 | } |
1612 | dongfang | 667 | |
2018 | - | 668 | if (request_display && txd_complete) { |
669 | LCD_printMenu(); |
||
670 | sendOutData('H', FC_ADDRESS, 2, &displayLine, sizeof(displayLine), |
||
671 | &displayBuff[displayLine * 20], 20); |
||
672 | displayLine++; |
||
673 | if (displayLine >= 4) |
||
674 | displayLine = 0; |
||
675 | request_display = FALSE; |
||
1821 | - | 676 | } |
1612 | dongfang | 677 | |
2018 | - | 678 | if (request_display1 && txd_complete) { |
679 | LCD_printMenu(); |
||
680 | sendOutData('L', FC_ADDRESS, 3, &menuItem, sizeof(menuItem), &maxMenuItem, |
||
681 | sizeof(maxMenuItem), displayBuff, sizeof(displayBuff)); |
||
682 | request_display1 = FALSE; |
||
1821 | - | 683 | } |
684 | |||
2018 | - | 685 | if (request_debugLabel != 0xFF) { // Texte für die Analogdaten |
1821 | - | 686 | uint8_t label[16]; // local sram buffer |
2018 | - | 687 | memcpy_P(label, ANALOG_LABEL[request_debugLabel], 16); // read lable from flash to sram buffer |
688 | sendOutData('A', FC_ADDRESS, 2, (uint8_t *) &request_debugLabel, |
||
689 | sizeof(request_debugLabel), label, 16); |
||
690 | request_debugLabel = 0xFF; |
||
1821 | - | 691 | } |
692 | |||
2018 | - | 693 | if (confirmFrame && txd_complete) { // Datensatz ohne checksum bestätigen |
694 | sendOutData('B', FC_ADDRESS, 1, (uint8_t*) &confirmFrame, sizeof(confirmFrame)); |
||
695 | confirmFrame = 0; |
||
1821 | - | 696 | } |
697 | |||
2018 | - | 698 | if (((debugData_interval && checkDelay(debugData_timer)) || request_debugData) |
1821 | - | 699 | && txd_complete) { |
2018 | - | 700 | sendOutData('D', FC_ADDRESS, 1, (uint8_t *) &debugOut, sizeof(debugOut)); |
701 | debugData_timer = setDelay(debugData_interval); |
||
702 | request_debugData = FALSE; |
||
1821 | - | 703 | } |
704 | |||
2018 | - | 705 | if (((data3D_interval && checkDelay(data3D_timer)) || request_data3D) |
1821 | - | 706 | && txd_complete) { |
2018 | - | 707 | sendOutData('C', FC_ADDRESS, 1, (uint8_t *) &data3D, sizeof(data3D)); |
708 | data3D.anglePitch = (int16_t) ((10 * angle[PITCH]) |
||
1821 | - | 709 | / GYRO_DEG_FACTOR_PITCHROLL); // convert to multiple of 0.1° |
2018 | - | 710 | data3D.angleRoll = (int16_t) ((10 * angle[ROLL]) |
1821 | - | 711 | / GYRO_DEG_FACTOR_PITCHROLL); // convert to multiple of 0.1° |
2018 | - | 712 | data3D.heading = (int16_t) ((10 * yawGyroHeading) / GYRO_DEG_FACTOR_YAW); // convert to multiple of 0.1° |
713 | data3D_timer = setDelay(data3D_interval); |
||
714 | request_data3D = FALSE; |
||
1821 | - | 715 | } |
716 | |||
2018 | - | 717 | if (request_externalControl && txd_complete) { |
718 | sendOutData('G', FC_ADDRESS, 1, (uint8_t *) &externalControl, |
||
1821 | - | 719 | sizeof(externalControl)); |
2018 | - | 720 | request_externalControl = FALSE; |
1821 | - | 721 | } |
722 | |||
1612 | dongfang | 723 | #ifdef USE_MK3MAG |
1887 | - | 724 | if((checkDelay(Compass_Timer)) && txd_complete) { |
1969 | - | 725 | toMk3Mag.Attitude[0] = (int16_t)((10 * angle[PITCH]) / GYRO_DEG_FACTOR_PITCHROLL); // approx. 0.1 deg |
726 | toMk3Mag.Attitude[1] = (int16_t)((10 * angle[ROLL]) / GYRO_DEG_FACTOR_PITCHROLL); // approx. 0.1 deg |
||
727 | toMk3Mag.UserParam[0] = dynamicParams.userParams[0]; |
||
728 | toMk3Mag.UserParam[1] = dynamicParams.userParams[1]; |
||
729 | toMk3Mag.CalState = compassCalState; |
||
2018 | - | 730 | sendOutData('w', MK3MAG_ADDRESS, 1,(uint8_t *) &toMk3Mag,sizeof(toMk3Mag)); |
1821 | - | 731 | // the last state is 5 and should be send only once to avoid multiple flash writing |
732 | if(compassCalState > 4) compassCalState = 0; |
||
2018 | - | 733 | compass_timer = setDelay(99); |
1821 | - | 734 | } |
1612 | dongfang | 735 | #endif |
736 | |||
2018 | - | 737 | if (request_motorTest && txd_complete) { |
738 | sendOutData('T', FC_ADDRESS, 0); |
||
739 | request_motorTest = FALSE; |
||
1821 | - | 740 | } |
1775 | - | 741 | |
1821 | - | 742 | if (request_PPMChannels && txd_complete) { |
2018 | - | 743 | sendOutData('P', FC_ADDRESS, 1, (uint8_t *) &PPM_in, sizeof(PPM_in)); |
1821 | - | 744 | request_PPMChannels = FALSE; |
745 | } |
||
746 | |||
747 | if (request_variables && txd_complete) { |
||
2018 | - | 748 | sendOutData('X', FC_ADDRESS, 1, (uint8_t *) &variables, sizeof(variables)); |
1821 | - | 749 | request_variables = FALSE; |
750 | } |
||
1612 | dongfang | 751 | } |