Subversion Repositories FlightCtrl

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1180 killagreg 1
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
2
// + Copyright (c) 04.2007 Holger Buss
3
// + Nur für den privaten Gebrauch
4
// + www.MikroKopter.com
5
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
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 (nicht-kommerziellen) Gebrauch zulässig ist.
8
// + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt
9
// + bzgl. der Nutzungsbedingungen aufzunehmen.
10
// + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen,
11
// + Verkauf von Luftbildaufnahmen, usw.
12
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
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
15
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
16
// + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts
17
// + auf anderen Webseiten oder sonstigen Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de"
18
// + eindeutig als Ursprung verlinkt werden
19
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
20
// + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion
21
// + Benutzung auf eigene Gefahr
22
// + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden
23
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
24
// + Die Portierung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur
25
// + mit unserer Zustimmung zulässig
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
47
// +  INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN// +  CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
48
// +  ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
49
// +  POSSIBILITY OF SUCH DAMAGE.
50
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
51
#include <avr/io.h>
52
#include <avr/interrupt.h>
53
#include <avr/wdt.h>
54
#include <stdarg.h>
55
#include <string.h>
56
 
57
#include "eeprom.h"
58
#include "main.h"
59
#include "menu.h"
60
#include "timer0.h"
61
#include "uart0.h"
62
#include "fc.h"
63
#include "rc.h"
64
#if defined (USE_KILLAGREG) || defined (USE_MK3MAG)
65
#include "ubx.h"
66
#endif
67
#ifdef USE_MK3MAG
68
#include "mk3mag.h"
69
#endif
70
 
71
 
72
#define FC_ADDRESS 1
73
#define NC_ADDRESS 2
74
#define MK3MAG_ADDRESS 3
75
 
76
#define FALSE   0
77
#define TRUE    1
78
 
79
//int8_t test __attribute__ ((section (".noinit")));
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;
87
uint8_t Request_PPMChannels     = FALSE;
88
uint8_t Request_MotorTest               = FALSE;
89
uint8_t DisplayLine = 0;
90
 
91
volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
92
volatile uint8_t rxd_buffer_locked = FALSE;
93
volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
94
volatile uint8_t txd_complete = TRUE;
95
volatile uint8_t ReceivedBytes = 0;
96
volatile uint8_t *pRxData = 0;
97
volatile uint8_t RxDataLen = 0;
98
 
99
uint8_t PcAccess = 100;
100
uint8_t MotorTest[4] = {0,0,0,0};
101
uint8_t ConfirmFrame;
102
 
103
typedef struct
104
{
105
        int16_t Heading;
106
} __attribute__((packed)) Heading_t;
107
 
108
DebugOut_t              DebugOut;
109
Data3D_t                Data3D;
110
ExternControl_t ExternControl;
111
UART_VersionInfo_t      UART_VersionInfo;
112
 
113
uint16_t DebugData_Timer;
114
uint16_t Data3D_Timer;
115
uint16_t DebugData_Interval = 500; // in 1ms
116
uint16_t Data3D_Interval = 0; // in 1ms
117
 
118
#ifdef USE_MK3MAG
119
int16_t Compass_Timer;
120
#endif
121
 
122
 
123
const uint8_t ANALOG_LABEL[32][16] =
124
{
125
   //1234567890123456
126
    "AngleNick       ", //0
127
    "AngleRoll       ",
128
    "AccNick         ",
129
    "AccRoll         ",
130
    "YawGyro         ",
131
    "Height Value    ", //5
132
    "AccZ            ",
133
    "Gas             ",
134
    "Compass Heading ",
135
    "Voltage         ",
136
    "Receiver Level  ", //10
137
    "YawGyro Heading ",
138
    "Motor Front     ",
139
    "Motor Rear      ",
140
    "Motor Left      ",
141
    "Motor Right     ", //15
142
    "                ",
143
    "                ",
144
    "                ",
145
    "CompassCalState ",
146
    "NickServo       ", //20
147
    "                ",
148
    "                ",
149
    "                ",
150
    "                ",
151
    "                ", //25
152
    "                ",
153
    "Kalman Max Drift",
154
    "                ",
155
    "                ",
156
    "GPS Nick        ", //30
157
    "GPSS Roll       "
158
};
159
 
160
 
161
 
162
/****************************************************************/
163
/*              Initialization of the USART0                    */
164
/****************************************************************/
165
void USART0_Init (void)
166
{
167
        uint8_t sreg = SREG;
168
        uint16_t ubrr = (uint16_t) ((uint32_t) SYSCLK/(8 * USART0_BAUD) - 1);
169
 
170
        // disable all interrupts before configuration
171
        cli();
172
 
173
        // disable RX-Interrupt
174
        UCSR0B &= ~(1 << RXCIE0);
175
        // disable TX-Interrupt
176
        UCSR0B &= ~(1 << TXCIE0);
177
 
178
        // set direction of RXD0 and TXD0 pins
179
        // set RXD0 (PD0) as an input pin
180
        PORTD |= (1 << PORTD0);
181
        DDRD &= ~(1 << DDD0);
182
        // set TXD0 (PD1) as an output pin
183
        PORTD |= (1 << PORTD1);
184
        DDRD |=  (1 << DDD1);
185
 
186
        // USART0 Baud Rate Register
187
        // set clock divider
188
        UBRR0H = (uint8_t)(ubrr >> 8);
189
        UBRR0L = (uint8_t)ubrr;
190
 
191
        // USART0 Control and Status Register A, B, C
192
 
193
        // enable double speed operation in
194
        UCSR0A |= (1 << U2X0);
195
        // enable receiver and transmitter in
196
        UCSR0B = (1 << TXEN0) | (1 << RXEN0);
197
        // set asynchronous mode
198
        UCSR0C &= ~(1 << UMSEL01);
199
        UCSR0C &= ~(1 << UMSEL00);
200
        // no parity
201
        UCSR0C &= ~(1 << UPM01);
202
        UCSR0C &= ~(1 << UPM00);
203
        // 1 stop bit
204
        UCSR0C &= ~(1 << USBS0);
205
        // 8-bit
206
        UCSR0B &= ~(1 << UCSZ02);
207
        UCSR0C |=  (1 << UCSZ01);
208
        UCSR0C |=  (1 << UCSZ00);
209
 
210
                // flush receive buffer
211
        while ( UCSR0A & (1<<RXC0) ) UDR0;
212
 
213
        // enable interrupts at the end
214
        // enable RX-Interrupt
215
        UCSR0B |= (1 << RXCIE0);
216
        // enable TX-Interrupt
217
        UCSR0B |= (1 << TXCIE0);
218
 
219
        // initialize the debug timer
220
        DebugData_Timer = SetDelay(DebugData_Interval);
221
 
222
        // unlock rxd_buffer
223
        rxd_buffer_locked = FALSE;
224
        pRxData = 0;
225
        RxDataLen = 0;
226
 
227
        // no bytes to send
228
        txd_complete = TRUE;
229
 
230
        #ifdef USE_MK3MAG
231
        Compass_Timer = SetDelay(220);
232
        #endif
233
 
234
        UART_VersionInfo.SWMajor = VERSION_MAJOR;
235
        UART_VersionInfo.SWMinor = VERSION_MINOR;
236
        UART_VersionInfo.SWPatch = VERSION_PATCH;
237
        UART_VersionInfo.ProtoMajor = VERSION_SERIAL_MAJOR;
238
        UART_VersionInfo.ProtoMinor = VERSION_SERIAL_MINOR;
239
 
240
        // restore global interrupt flags
241
    SREG = sreg;
242
}
243
 
244
/****************************************************************/
245
/*               USART0 transmitter ISR                         */
246
/****************************************************************/
247
ISR(USART0_TX_vect)
248
{
249
        static uint16_t ptr_txd_buffer = 0;
250
        uint8_t tmp_tx;
251
        if(!txd_complete) // transmission not completed
252
        {
253
                ptr_txd_buffer++;                    // die [0] wurde schon gesendet
254
                tmp_tx = txd_buffer[ptr_txd_buffer];
255
                // if terminating character or end of txd buffer was reached
256
                if((tmp_tx == '\r') || (ptr_txd_buffer == TXD_BUFFER_LEN))
257
                {
258
                        ptr_txd_buffer = 0; // reset txd pointer
259
                        txd_complete = 1; // stop transmission
260
                }
261
                UDR0 = tmp_tx; // send current byte will trigger this ISR again
262
        }
263
        // transmission completed
264
        else ptr_txd_buffer = 0;
265
}
266
 
267
/****************************************************************/
268
/*               USART0 receiver ISR                            */
269
/****************************************************************/
270
ISR(USART0_RX_vect)
271
{
272
        static uint16_t crc;
273
        static uint8_t ptr_rxd_buffer = 0;
274
        uint8_t crc1, crc2;
275
        uint8_t c;
276
 
277
        c = UDR0;  // catch the received byte
278
 
279
        #if (defined (USE_KILLAGREG) || defined (USE_MK3MAG))
280
        // If the cpu is not an Atmega644P the ublox module should be conneced to rxd of the 1st uart.
281
        if(CPUType != ATMEGA644P) ubx_parser(c);
282
        #endif
283
 
284
        if(rxd_buffer_locked) return; // if rxd buffer is locked immediately return
285
 
286
        // the rxd buffer is unlocked
287
        if((ptr_rxd_buffer == 0) && (c == '#')) // if rxd buffer is empty and syncronisation character is received
288
        {
289
                rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer
290
                crc = c; // init crc
291
        }
292
        #if 0
293
        else if (ptr_rxd_buffer == 1) // handle address
294
        {
295
                rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
296
                crc += c; // update crc
297
        }
298
        #endif
299
        else if (ptr_rxd_buffer < RXD_BUFFER_LEN) // collect incomming bytes
300
        {
301
                if(c != '\r') // no termination character
302
                {
303
                        rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
304
                        crc += c; // update crc
305
                }
306
                else // termination character was received
307
                {
308
                        // the last 2 bytes are no subject for checksum calculation
309
                        // they are the checksum itself
310
                        crc -= rxd_buffer[ptr_rxd_buffer-2];
311
                        crc -= rxd_buffer[ptr_rxd_buffer-1];
312
                        // calculate checksum from transmitted data
313
                        crc %= 4096;
314
                        crc1 = '=' + crc / 64;
315
                        crc2 = '=' + crc % 64;
316
                        // compare checksum to transmitted checksum bytes
317
                        if((crc1 == rxd_buffer[ptr_rxd_buffer-2]) && (crc2 == rxd_buffer[ptr_rxd_buffer-1]))
318
                        {   // checksum valid
319
                                rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character
320
                                ReceivedBytes = ptr_rxd_buffer + 1;// store number of received bytes
321
                                rxd_buffer_locked = TRUE;          // lock the rxd buffer
322
                                // if 2nd byte is an 'R' enable watchdog that will result in an reset
323
                                if(rxd_buffer[2] == 'R') {wdt_enable(WDTO_250MS);} // Reset-Commando
324
                        }
325
                        else
326
                        {       // checksum invalid
327
                                rxd_buffer_locked = FALSE; // unlock rxd buffer
328
                        }
329
                        ptr_rxd_buffer = 0; // reset rxd buffer pointer
330
                }
331
        }
332
        else // rxd buffer overrun
333
        {
334
                ptr_rxd_buffer = 0; // reset rxd buffer
335
                rxd_buffer_locked = FALSE; // unlock rxd buffer
336
        }
337
 
338
}
339
 
340
 
341
// --------------------------------------------------------------------------
342
void AddCRC(uint16_t datalen)
343
{
344
        uint16_t tmpCRC = 0, i;
345
        for(i = 0; i < datalen; i++)
346
        {
347
                tmpCRC += txd_buffer[i];
348
        }
349
        tmpCRC %= 4096;
350
        txd_buffer[i++] = '=' + tmpCRC / 64;
351
        txd_buffer[i++] = '=' + tmpCRC % 64;
352
        txd_buffer[i++] = '\r';
353
        txd_complete = FALSE;
354
        UDR0 = txd_buffer[0]; // initiates the transmittion (continued in the TXD ISR)
355
}
356
 
357
 
358
 
359
// --------------------------------------------------------------------------
360
void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) // uint8_t *pdata, uint8_t len, ...
361
{
362
        va_list ap;
363
        uint16_t pt = 0;
364
        uint8_t a,b,c;
365
        uint8_t ptr = 0;
366
 
367
        uint8_t *pdata = 0;
368
        int len = 0;
369
 
370
        txd_buffer[pt++] = '#';                 // Start character
371
        txd_buffer[pt++] = 'a' + addr;  // Address (a=0; b=1,...)
372
        txd_buffer[pt++] = cmd;                 // Command
373
 
374
        va_start(ap, numofbuffers);
375
        if(numofbuffers)
376
        {
377
                pdata = va_arg(ap, uint8_t*);
378
                len = va_arg(ap, int);
379
                ptr = 0;
380
                numofbuffers--;
381
        }
382
 
383
        while(len)
384
        {
385
                if(len)
386
                {
387
                        a = pdata[ptr++];
388
                        len--;
389
                        if((!len) && numofbuffers)
390
                        {
391
                                pdata = va_arg(ap, uint8_t*);
392
                                len = va_arg(ap, int);
393
                                ptr = 0;
394
                                numofbuffers--;
395
                        }
396
                }
397
                else a = 0;
398
                if(len)
399
                {
400
                        b = pdata[ptr++];
401
                        len--;
402
                        if((!len) && numofbuffers)
403
                        {
404
                                pdata = va_arg(ap, uint8_t*);
405
                                len = va_arg(ap, int);
406
                                ptr = 0;
407
                                numofbuffers--;
408
                        }
409
                }
410
                else b = 0;
411
                if(len)
412
                {
413
                        c = pdata[ptr++];
414
                        len--;
415
                        if((!len) && numofbuffers)
416
                        {
417
                                pdata = va_arg(ap, uint8_t*);
418
                                len = va_arg(ap, int);
419
                                ptr = 0;
420
                                numofbuffers--;
421
                        }
422
                }
423
                else c = 0;
424
                txd_buffer[pt++] = '=' + (a >> 2);
425
                txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
426
                txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
427
                txd_buffer[pt++] = '=' + ( c & 0x3f);
428
        }
429
        va_end(ap);
430
        AddCRC(pt); // add checksum after data block and initates the transmission
431
}
432
 
433
 
434
// --------------------------------------------------------------------------
435
void Decode64(void)
436
{
437
        uint8_t a,b,c,d;
438
        uint8_t x,y,z;
439
        uint8_t ptrIn = 3;
440
        uint8_t ptrOut = 3;
441
        uint8_t len = ReceivedBytes - 6;
442
 
443
        while(len)
444
        {
445
                a = rxd_buffer[ptrIn++] - '=';
446
                b = rxd_buffer[ptrIn++] - '=';
447
                c = rxd_buffer[ptrIn++] - '=';
448
                d = rxd_buffer[ptrIn++] - '=';
449
                //if(ptrIn > ReceivedBytes - 3) break;
450
 
451
                x = (a << 2) | (b >> 4);
452
                y = ((b & 0x0f) << 4) | (c >> 2);
453
                z = ((c & 0x03) << 6) | d;
454
 
455
                if(len--) rxd_buffer[ptrOut++] = x; else break;
456
                if(len--) rxd_buffer[ptrOut++] = y; else break;
457
                if(len--) rxd_buffer[ptrOut++] = z; else break;
458
        }
459
        pRxData = &rxd_buffer[3];
460
        RxDataLen = ptrOut - 3;
461
}
462
 
463
 
464
// --------------------------------------------------------------------------
465
void USART0_ProcessRxData(void)
466
{
467
        // if data in the rxd buffer are not locked immediately return
468
        if(!rxd_buffer_locked) return;
469
 
470
        uint8_t tempchar1, tempchar2;
471
 
472
        Decode64(); // decode data block in rxd_buffer
473
 
474
        switch(rxd_buffer[1] - 'a')
475
        {
476
                case FC_ADDRESS:
477
 
478
                switch(rxd_buffer[2])
479
                {
480
                        #ifdef USE_MK3MAG
481
                        case 'K':// compass value
482
                                CompassHeading = ((Heading_t *)pRxData)->Heading;
483
                                CompassOffCourse = ((540 + CompassHeading - CompassCourse) % 360) - 180;
484
                                break;
485
                        #endif
486
 
487
                        case 't':// motor test
488
                                memcpy(&MotorTest[0], (uint8_t*)pRxData, sizeof(MotorTest));
489
                                //Request_MotorTest = TRUE;
490
                                PcAccess = 255;
491
                                break;
492
 
493
                        case 'p': // get PPM channels
494
                                Request_PPMChannels = TRUE;
495
                                break;
496
 
497
                        case 'q':// request settings
498
                                if(pRxData[0] == 0xFF)
499
                                {
500
                                        pRxData[0] = GetParamByte(PID_ACTIVE_SET);
501
                                }
502
                                // limit settings range
503
                                if(pRxData[0] < 1) pRxData[0] = 1; // limit to 1
504
                                else if(pRxData[0] > 5) pRxData[0] = 5; // limit to 5
505
                                // load requested parameter set
506
                                ParamSet_ReadFromEEProm(pRxData[0]);
507
 
508
                                tempchar1 = pRxData[0];
509
                                tempchar2 = EEPARAM_VERSION;
510
                                while(!txd_complete); // wait for previous frame to be sent
511
                                SendOutData('Q', FC_ADDRESS,3, &tempchar1, sizeof(tempchar1), &tempchar2, sizeof(tempchar2), (uint8_t *) &ParamSet, sizeof(ParamSet));
512
                                break;
513
 
514
                        case 's': // save settings
515
                                if(!(MKFlags & MKFLAG_MOTOR_RUN)) // save settings only if motors ar off
516
                                {
517
                                        if((1 <= pRxData[0]) && (pRxData[0] <= 5) && (pRxData[1] == EEPARAM_VERSION)) // check for setting to be in range and version of settings
518
                                        {
519
                                                memcpy(&ParamSet, (uint8_t*)&pRxData[2], sizeof(ParamSet));
520
                                                ParamSet_WriteToEEProm(pRxData[0]);
521
                                                TurnOver180Nick = (int32_t) ParamSet.AngleTurnOverNick * 2500L;
522
                                                TurnOver180Roll = (int32_t) ParamSet.AngleTurnOverRoll * 2500L;
523
                                                tempchar1 = GetActiveParamSet();
524
                                                Beep(tempchar1);
525
                                        }
526
                                        else
527
                                        {
528
                                                tempchar1 = 0;  //indicate bad data
529
                                        }
530
                                        while(!txd_complete); // wait for previous frame to be sent
531
                                        SendOutData('S', FC_ADDRESS,1, &tempchar1, sizeof(tempchar1));
532
                                }
533
                                break;
534
 
535
                        default:
536
                                //unsupported command received
537
                                break;
538
                } // case FC_ADDRESS:
539
 
540
                default: // any Slave Address
541
 
542
                switch(rxd_buffer[2])
543
                {
544
                        case 'a':// request for labels of the analog debug outputs
545
                                Request_DebugLabel = pRxData[0];
546
                                if(Request_DebugLabel > 31) Request_DebugLabel = 31;
547
                                PcAccess = 255;
548
                                break;
549
 
550
                        case 'b': // submit extern control
551
                                memcpy(&ExternControl, (uint8_t*)pRxData, sizeof(ExternControl));
552
                                ConfirmFrame = ExternControl.Frame;
553
                                PcAccess = 255;
554
                                break;
555
 
556
                        case 'h':// request for display columns
557
                                PcAccess = 255;
558
                                RemoteKeys |= pRxData[0];
559
                                if(RemoteKeys) DisplayLine = 0;
560
                                Request_Display = TRUE;
561
                                break;
562
 
563
                        case 'l':// request for display columns
564
                                PcAccess = 255;
565
                                MenuItem = pRxData[0];
566
                                Request_Display1 = TRUE;
567
                                break;
568
 
569
                        case 'v': // request for version and board release
570
                                Request_VerInfo = TRUE;
571
                                break;
572
 
573
                        case 'g':// get external control data
574
                                Request_ExternalControl = TRUE;
575
                                break;
576
 
577
                        case 'd': // request for the debug data
578
                                DebugData_Interval = (uint16_t) pRxData[0] * 10;
579
                                if(DebugData_Interval > 0) Request_DebugData = TRUE;
580
                                break;
581
 
582
                        case 'c': // request for the 3D data
583
                                Data3D_Interval = (uint16_t) pRxData[0] * 10;
584
                                if(Data3D_Interval > 0) Request_Data3D = TRUE;
585
                                break;
586
 
587
                        default:
588
                                //unsupported command received
589
                                break;
590
                }
591
                break; // default:
592
        }
593
        // unlock the rxd buffer after processing
594
        pRxData = 0;
595
        RxDataLen = 0;
596
        rxd_buffer_locked = FALSE;
597
}
598
 
599
//############################################################################
600
//Routine für die Serielle Ausgabe
601
int16_t uart_putchar (int8_t c)
602
//############################################################################
603
{
604
        if (c == '\n')
605
                uart_putchar('\r');
606
        // wait until previous character was send
607
        loop_until_bit_is_set(UCSR0A, UDRE0);
608
        // send character
609
        UDR0 = c;
610
        return (0);
611
}
612
 
613
 
614
//---------------------------------------------------------------------------------------------
615
void USART0_TransmitTxData(void)
616
{
617
        if(!txd_complete) return;
618
 
619
        if(Request_VerInfo && txd_complete)
620
        {
621
                SendOutData('V', FC_ADDRESS, 1, (uint8_t *) &UART_VersionInfo, sizeof(UART_VersionInfo));
622
                Request_VerInfo = FALSE;
623
        }
624
        if(Request_Display && txd_complete)
625
        {
626
                LCD_PrintMenu();
627
                SendOutData('H', FC_ADDRESS, 2, &DisplayLine, sizeof(DisplayLine), &DisplayBuff[DisplayLine * 20], 20);
628
                DisplayLine++;
629
                if(DisplayLine >= 4) DisplayLine = 0;
630
                Request_Display = FALSE;
631
        }
632
        if(Request_Display1 && txd_complete)
633
        {
634
                LCD_PrintMenu();
635
                SendOutData('L', FC_ADDRESS, 3, &MenuItem, sizeof(MenuItem), &MaxMenuItem, sizeof(MaxMenuItem), DisplayBuff, sizeof(DisplayBuff));
636
                Request_Display1 = FALSE;
637
        }
638
        if(Request_DebugLabel != 0xFF) // Texte für die Analogdaten
639
        {
640
                SendOutData('A', FC_ADDRESS, 2, (uint8_t *) &Request_DebugLabel, sizeof(Request_DebugLabel), ANALOG_LABEL[Request_DebugLabel], 16);
641
                Request_DebugLabel = 0xFF;
642
        }
643
        if(ConfirmFrame && txd_complete)   // Datensatz ohne CRC bestätigen
644
        {
645
                SendOutData('B', FC_ADDRESS, 1, (uint8_t*)&ConfirmFrame, sizeof(ConfirmFrame));
646
                ConfirmFrame = 0;
647
        }
648
        if( ((DebugData_Interval && CheckDelay(DebugData_Timer)) || Request_DebugData) && txd_complete)
649
        {
650
                SendOutData('D', FC_ADDRESS, 1,(uint8_t *) &DebugOut, sizeof(DebugOut));
651
                DebugData_Timer = SetDelay(DebugData_Interval);
652
                Request_DebugData = FALSE;
653
    }
654
    if( ((Data3D_Interval && CheckDelay(Data3D_Timer)) || Request_Data3D) && txd_complete)
655
        {
656
                SendOutData('C', FC_ADDRESS, 1,(uint8_t *) &Data3D, sizeof(Data3D));
657
                Data3D.AngleNick = (int16_t)((10 * IntegralGyroNick) / GYRO_DEG_FACTOR); // convert to multiple of 0.1°
658
                Data3D.AngleRoll = (int16_t)((10 * IntegralGyroRoll) / GYRO_DEG_FACTOR); // convert to multiple of 0.1°
659
                Data3D.Heading   = (int16_t)((10 * YawGyroHeading)   / GYRO_DEG_FACTOR); // convert to multiple of 0.1°
660
                Data3D_Timer = SetDelay(Data3D_Interval);
661
                Request_Data3D = FALSE;
662
    }
663
        if(Request_ExternalControl && txd_complete)
664
        {
665
                SendOutData('G', FC_ADDRESS, 1,(uint8_t *) &ExternControl, sizeof(ExternControl));
666
                Request_ExternalControl = FALSE;
667
        }
668
 
669
        #ifdef USE_MK3MAG
670
    if((CheckDelay(Compass_Timer)) && txd_complete)
671
        {
1186 killagreg 672
                ToMk3Mag.Attitude[0] = (int16_t)((10 * IntegralGyroNick) / GYRO_DEG_FACTOR);  // approx. 0.1 deg
673
                ToMk3Mag.Attitude[1] = (int16_t)((10 * IntegralGyroRoll) / GYRO_DEG_FACTOR);  // approx. 0.1 deg
1180 killagreg 674
                ToMk3Mag.UserParam[0] = FCParam.UserParam1;
675
                ToMk3Mag.UserParam[1] = FCParam.UserParam2;
676
                ToMk3Mag.CalState = CompassCalState;
677
                SendOutData('w', MK3MAG_ADDRESS, 1,(uint8_t *) &ToMk3Mag,sizeof(ToMk3Mag));
678
                // the last state is 5 and should be send only once to avoid multiple flash writing
679
                if(CompassCalState > 4)  CompassCalState = 0;
680
                Compass_Timer = SetDelay(99);
681
        }
682
        #endif
683
        if(Request_MotorTest && txd_complete)
684
        {
685
                SendOutData('T', FC_ADDRESS, 0);
686
                Request_MotorTest = FALSE;
687
        }
688
        if(Request_PPMChannels && txd_complete)
689
        {
690
                SendOutData('P', FC_ADDRESS, 1, (uint8_t *)&PPM_in, sizeof(PPM_in));
691
                Request_PPMChannels = FALSE;
692
        }
693
}
694