Subversion Repositories FlightCtrl

Rev

Rev 885 | Show entire file | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed

Rev 885 Rev 886
Line 1... Line 1...
1
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
1
 // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
2
// + Copyright (c) 04.2007 Holger Buss
2
// + Copyright (c) 04.2007 Holger Buss
3
// + only for non-profit use
3
// + only for non-profit use
4
// + www.MikroKopter.com
4
// + www.MikroKopter.com
5
// + see the File "License.txt" for further Informations
5
// + see the File "License.txt" for further Informations
6
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
6
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
Line -... Line 7...
-
 
7
 
-
 
8
#include <avr/io.h>
-
 
9
#include <avr/interrupt.h>
-
 
10
#include <avr/wdt.h>
-
 
11
 
7
 
12
#include "eeprom.h"
-
 
13
#include "main.h"
-
 
14
#include "menu.h"
8
#include "main.h"
15
#include "timer0.h"
-
 
16
#include "uart.h"
-
 
17
#include "fc.h"
-
 
18
#include "_Settings.h"
-
 
19
#include "rc.h"
-
 
20
#ifdef USE_KILLAGREG
-
 
21
#include "ubx.h"
-
 
22
#endif
-
 
23
#if !defined(USE_KILLAGREG) && !defined (USE_NAVICTRL)
-
 
24
#include "mk3mag.h"
-
 
25
#endif
Line 9... Line -...
9
#include "uart.h"
-
 
10
 
-
 
11
unsigned char DebugGetAnforderung = 0,DebugDisplayAnforderung = 0,DebugDataAnforderung = 0,GetVersionAnforderung = 0;
-
 
12
unsigned volatile char SioTmp = 0;
-
 
13
unsigned volatile char SendeBuffer[MAX_SENDE_BUFF];
-
 
14
unsigned volatile char RxdBuffer[MAX_EMPFANGS_BUFF];
-
 
15
unsigned volatile char NMEABuffer[MAX_EMPFANGS_BUFF];
-
 
16
unsigned volatile char NeuerDatensatzEmpfangen = 0;
-
 
17
unsigned volatile char NeueKoordinateEmpfangen = 0;
-
 
18
unsigned volatile char UebertragungAbgeschlossen = 1;
-
 
19
unsigned volatile char CntCrcError = 0;
-
 
20
unsigned volatile char AnzahlEmpfangsBytes = 0;
-
 
21
unsigned volatile char PC_DebugTimeout = 0;
-
 
22
unsigned char RemotePollDisplayLine = 0;
-
 
23
unsigned char NurKanalAnforderung = 0;
-
 
24
unsigned char DebugTextAnforderung = 255;
-
 
25
unsigned char PcZugriff = 100;
-
 
26
unsigned char MotorTest[4] = {0,0,0,0};
-
 
27
unsigned char DubWiseKeys[4] = {0,0,0,0};
-
 
28
unsigned char MeineSlaveAdresse;
-
 
29
unsigned char ConfirmFrame;
-
 
30
struct str_DebugOut    DebugOut;
-
 
31
struct str_ExternControl  ExternControl;
-
 
Line -... Line 26...
-
 
26
 
-
 
27
 
-
 
28
 
-
 
29
#define FALSE   0
-
 
30
#define TRUE    1
-
 
31
 
-
 
32
//int8_t test __attribute__ ((section (".noinit")));
-
 
33
uint8_t RequestVerInfo                  = FALSE;
-
 
34
uint8_t RequestExternalControl  = FALSE;
-
 
35
uint8_t RequestDisplay                  = FALSE;
-
 
36
uint8_t RequestDebugData                = FALSE;
-
 
37
uint8_t RequestDebugLabel               = 255;
-
 
38
uint8_t RequestChannelOnly              = FALSE;
-
 
39
uint8_t RemotePollDisplayLine   = 0;
-
 
40
 
-
 
41
volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
-
 
42
volatile uint8_t rxd_buffer_locked = FALSE;
-
 
43
volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
-
 
44
volatile uint8_t txd_complete = TRUE;
-
 
45
volatile uint8_t ReceivedBytes = 0;
-
 
46
 
-
 
47
 
-
 
48
uint8_t PcAccess = 100;
-
 
49
uint8_t MotorTest[4] = {0,0,0,0};
-
 
50
uint8_t DubWiseKeys[4] = {0,0,0,0};
-
 
51
uint8_t MySlaveAddr = 0;
-
 
52
uint8_t ConfirmFrame;
-
 
53
 
-
 
54
DebugOut_t              DebugOut;
-
 
55
ExternControl_t ExternControl;
-
 
56
VersionInfo_t   VersionInfo;
-
 
57
 
32
struct str_VersionInfo VersionInfo;
58
int16_t  Debug_Timer;
-
 
59
 
Line -... Line 60...
-
 
60
#if  !defined (USE_KILLAGREG)  && !defined (USE_NAVICTRL)
33
struct str_WinkelOut WinkelOut;
61
int16_t Compass_Timer;
34
 
62
#endif
35
int Debug_Timer,Kompass_Timer;
63
 
36
 
64
 
37
const unsigned char ANALOG_TEXT[32][16] =
65
const uint8_t ANALOG_LABEL[32][16] =
38
{
66
{
39
   //1234567890123456 
67
   //1234567890123456
40
    "IntegralNick    ", //0
68
    "IntegralPitch   ", //0
41
    "IntegralRoll    ",
69
    "IntegralRoll    ",
42
    "AccNick         ",
70
    "AccPitch        ",
43
    "AccRoll         ",
71
    "AccRoll         ",
44
    "GyroGier        ",
72
    "GyroYaw         ",
45
    "HoehenWert      ", //5
73
    "ReadingHeight   ", //5
46
    "AccZ            ",
74
    "AccZ            ",
47
    "Gas             ",
75
    "Thrust          ",
48
    "KompassValue    ",
76
    "CompassHeading  ",
49
    "Spannung        ",
77
    "Voltage         ",
50
    "Empfang         ", //10
78
    "Receiver Level  ", //10
51
    "Ersatzkompass   ",
79
    "YawGyroHeading  ",
52
    "Motor_Vorne     ",
80
    "Motor_Front     ",
53
    "Motor_Hinten    ",
81
    "Motor_Rear      ",
54
    "Motor_Links     ",
82
    "Motor_Right     ",
55
    "Motor_Rechts    ", //15
83
    "Motor_Left      ", //15
56
    "Acc_Z           ",
84
    "Acc_Z           ",
57
    "Distance        ",
85
    "SPI Error       ",
58
    "OsdBar          ",
86
    "SPI Ok          ",
59
    "MK3Mag CalState ",
87
    "                ",
60
    "Servo           ", //20
88
    "Servo           ", //20
61
    "Nick            ",
89
    "Pitch           ",
62
    "Roll            ",
90
    "Roll            ",
63
    "                ",
91
    "                ",
64
    "                ",
92
    "                ",
65
    "                ", //25
93
    "                ", //25
66
    "                ",
94
    "                ",
67
    "                ",
95
    "                ",
68
    "                ",
96
    "                ",
Line 69... Line 97...
69
    "                ",
97
    "                ",
70
    "GPS_Nick        ", //30
98
    "GPS_Pitch       ", //30
71
    "GPS_Roll        "
99
    "GPS_Roll        "
72
};
100
};
73
 
101
 
-
 
102
 
-
 
103
 
-
 
104
/****************************************************************/
-
 
105
/*              Initialization of the USART0                    */
-
 
106
/****************************************************************/
-
 
107
void USART0_Init (void)
-
 
108
{
-
 
109
        uint8_t sreg = SREG;
-
 
110
        uint16_t ubrr = (uint16_t) ((uint32_t) SYSCLK/(8 * USART0_BAUD) - 1);
-
 
111
 
-
 
112
        // disable all interrupts before configuration
-
 
113
        cli();
-
 
114
 
-
 
115
        // disable RX-Interrupt
-
 
116
        UCSR0B &= ~(1 << RXCIE0);
74
 
117
        // disable TX-Interrupt
-
 
118
        UCSR0B &= ~(1 << TXCIE0);
75
 
119
 
-
 
120
        // set direction of RXD0 and TXD0 pins
76
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
121
        // set RXD0 (PD0) as an input pin
-
 
122
        PORTD |= (1 << PORTD0);
-
 
123
        DDRD &= ~(1 << DDD0);
-
 
124
        // set TXD0 (PD1) as an output pin
77
//++ Sende-Part der Datenübertragung
125
        PORTD |= (1 << PORTD1);
78
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
126
        DDRD |=  (1 << DDD1);
-
 
127
 
79
SIGNAL(INT_VEC_TX)
128
        // USART0 Baud Rate Register
-
 
129
        // set clock divider
-
 
130
        UBRR0H = (uint8_t)(ubrr >> 8);
80
{
131
        UBRR0L = (uint8_t)ubrr;
-
 
132
 
-
 
133
        // USART0 Control and Status Register A, B, C
-
 
134
 
81
 static unsigned int ptr = 0;
135
        // enable double speed operation in
-
 
136
        UCSR0A |= (1 << U2X0);
-
 
137
        // enable receiver and transmitter in
82
 unsigned char tmp_tx;
138
        UCSR0B = (1 << TXEN0) | (1 << RXEN0);
83
 if(!UebertragungAbgeschlossen)  
139
        // set asynchronous mode
84
  {
140
        UCSR0C &= ~(1 << UMSEL01);
-
 
141
        UCSR0C &= ~(1 << UMSEL00);
-
 
142
        // no parity
85
   ptr++;                    // die [0] wurde schon gesendet
143
        UCSR0C &= ~(1 << UPM01);
-
 
144
        UCSR0C &= ~(1 << UPM00);
-
 
145
        // 1 stop bit
-
 
146
        UCSR0C &= ~(1 << USBS0);
-
 
147
        // 8-bit
-
 
148
        UCSR0B &= ~(1 << UCSZ02);
-
 
149
        UCSR0C |=  (1 << UCSZ01);
-
 
150
        UCSR0C |=  (1 << UCSZ00);
-
 
151
 
-
 
152
                // flush receive buffer
-
 
153
        while ( UCSR0A & (1<<RXC0) ) UDR0;
-
 
154
 
-
 
155
        // enable interrupts at the end
-
 
156
        // enable RX-Interrupt
-
 
157
        UCSR0B |= (1 << RXCIE0);
-
 
158
        // enable TX-Interrupt
-
 
159
        UCSR0B |= (1 << TXCIE0);
-
 
160
 
-
 
161
        rxd_buffer_locked = FALSE;
86
   tmp_tx = SendeBuffer[ptr];  
162
        txd_complete = TRUE;
-
 
163
 
87
   if((tmp_tx == '\r') || (ptr == MAX_SENDE_BUFF))
164
        Debug_Timer = SetDelay(200);
88
    {
165
 
Line 89... Line 166...
89
     ptr = 0;
166
        #if  !defined (USE_KILLAGREG)  && !defined (USE_NAVICTRL)
90
     UebertragungAbgeschlossen = 1;
167
        Compass_Timer = SetDelay(220);
91
    }
168
        #endif
92
   UDR = tmp_tx;
169
 
93
  }
170
        // restore global interrupt flags
94
  else ptr = 0;
171
    SREG = sreg;
-
 
172
}
-
 
173
 
-
 
174
/****************************************************************/
-
 
175
/*               USART0 transmitter ISR                         */
95
}
176
/****************************************************************/
-
 
177
ISR(USART0_TX_vect)
-
 
178
{
-
 
179
        static uint16_t ptr_txd_buffer = 0;
96
 
180
        uint8_t tmp_tx;
-
 
181
        if(!txd_complete) // transmission not completed
-
 
182
        {
-
 
183
                ptr_txd_buffer++;                    // die [0] wurde schon gesendet
-
 
184
                tmp_tx = txd_buffer[ptr_txd_buffer];
-
 
185
                // if terminating character or end of txd buffer was reached
97
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
186
                if((tmp_tx == '\r') || (ptr_txd_buffer == TXD_BUFFER_LEN))
-
 
187
                {
98
//++ Empfangs-Part der Datenübertragung, incl. CRC-Auswertung
188
                        ptr_txd_buffer = 0; // reset txd pointer
99
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
189
                        txd_complete = 1; // stop transmission
100
SIGNAL(INT_VEC_RX)
190
                }
-
 
191
                UDR0 = tmp_tx; // send current byte will trigger this ISR again
101
{
192
        }
102
 static unsigned int crc;
193
        // transmission completed
103
 static unsigned char crc1,crc2,buf_ptr;
194
        else ptr_txd_buffer = 0;
104
 static unsigned char UartState = 0;
195
}
105
 unsigned char CrcOkay = 0;
196
 
106
 
197
/****************************************************************/
-
 
198
/*               USART0 receiver ISR                            */
107
 SioTmp = UDR;
199
/****************************************************************/
-
 
200
ISR(USART0_RX_vect)
108
 if(buf_ptr >= MAX_EMPFANGS_BUFF)    UartState = 0;
201
{
109
 if(SioTmp == '\r' && UartState == 2)
-
 
110
  {
202
        static uint16_t crc;
111
   UartState = 0;
203
        static uint8_t ptr_rxd_buffer = 0;
-
 
204
        uint8_t crc1, crc2;
-
 
205
        uint8_t c;
112
   crc -= RxdBuffer[buf_ptr-2];
206
 
113
   crc -= RxdBuffer[buf_ptr-1];
207
        c = UDR0;  // catch the received byte
-
 
208
 
114
   crc %= 4096;
209
        #ifdef USE_KILLAGREG
-
 
210
        // If the FC 1.0 cpu is used the ublox module should be conneced to rxd of the 1st uart.
-
 
211
        // The FC 1.1 /1.2 has the ATMEGA644p cpu with a 2nd uart to which the ublox should be connected.
-
 
212
        #if defined (__AVR_ATmega644P__)
115
   crc1 = '=' + crc / 64;
213
        if(BoardRelease == 10) ubx_parser(c);
116
   crc2 = '=' + crc % 64;
214
        #else
117
   CrcOkay = 0;
215
        ubx_parser(c);
-
 
216
        #endif
-
 
217
        #endif // USE_KILLAGREG
118
   if((crc1 == RxdBuffer[buf_ptr-2]) && (crc2 == RxdBuffer[buf_ptr-1])) CrcOkay = 1; else { CrcOkay = 0; CntCrcError++;};
218
 
119
   if(!NeuerDatensatzEmpfangen && CrcOkay) // Datensatz schon verarbeitet
219
        if(rxd_buffer_locked) return; // if rxd buffer is locked immediately return
-
 
220
 
-
 
221
        // the rxd buffer is unlocked
-
 
222
        if((ptr_rxd_buffer == 0) && (c == '#')) // if rxd buffer is empty and syncronisation character is received
120
    {
223
        {
121
     NeuerDatensatzEmpfangen = 1;
224
                rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer
122
         AnzahlEmpfangsBytes = buf_ptr;
225
                crc = c; // init crc
123
     RxdBuffer[buf_ptr] = '\r';
226
        }
-
 
227
        #if 0
124
         if(RxdBuffer[2] == 'R') wdt_enable(WDTO_250MS); // Reset-Commando
228
        else if (ptr_rxd_buffer == 1) // handle address
-
 
229
        {
125
        }                                
230
                rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
126
  }
231
                crc += c; // update crc
-
 
232
        }
127
  else
233
        #endif
-
 
234
        else if (ptr_rxd_buffer < RXD_BUFFER_LEN) // collect incomming bytes
-
 
235
        {
128
  switch(UartState)
236
                if(c != '\r') // no termination character
129
  {
237
                {
130
   case 0:
238
                        rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
-
 
239
                        crc += c; // update crc
131
          if(SioTmp == '#' && !NeuerDatensatzEmpfangen) UartState = 1;  // Startzeichen und Daten schon verarbeitet
240
                }
-
 
241
                else // termination character was received
132
                  buf_ptr = 0;
242
                {
133
                  RxdBuffer[buf_ptr++] = SioTmp;
243
                        // the last 2 bytes are no subject for checksum calculation
-
 
244
                        // they are the checksum itself
134
                  crc = SioTmp;
245
                        crc -= rxd_buffer[ptr_rxd_buffer-2];
135
          break;
246
                        crc -= rxd_buffer[ptr_rxd_buffer-1];
-
 
247
                        // calculate checksum from transmitted data
-
 
248
                        crc %= 4096;
-
 
249
                        crc1 = '=' + crc / 64;
-
 
250
                        crc2 = '=' + crc % 64;
-
 
251
                        // compare checksum to transmitted checksum bytes
136
   case 1: // Adresse auswerten
252
                        if((crc1 == rxd_buffer[ptr_rxd_buffer-2]) && (crc2 == rxd_buffer[ptr_rxd_buffer-1]))
137
                  UartState++;
253
                        {   // checksum valid
-
 
254
                                rxd_buffer_locked = TRUE;          // lock the rxd buffer
138
                  RxdBuffer[buf_ptr++] = SioTmp;
255
                                ReceivedBytes = ptr_rxd_buffer;    // store number of received bytes
-
 
256
                                rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character
139
                  crc += SioTmp;
257
                                // if 2nd byte is an 'R' enable watchdog that will result in an reset
-
 
258
                                if(rxd_buffer[2] == 'R') {wdt_enable(WDTO_250MS);} // Reset-Commando
140
                  break;
259
                        }
-
 
260
                        else
141
   case 2: //  Eingangsdaten sammeln
261
                        {       // checksum invalid
-
 
262
                                rxd_buffer_locked = FALSE; // unlock rxd buffer
142
                  RxdBuffer[buf_ptr] = SioTmp;
263
                        }
-
 
264
                        ptr_rxd_buffer = 0; // reset rxd buffer pointer
143
                  if(buf_ptr < MAX_EMPFANGS_BUFF) buf_ptr++;
265
                }
Line 144... Line 266...
144
                  else UartState = 0;
266
        }
145
                  crc += SioTmp;
267
        else // rxd buffer overrun
146
                  break;
268
        {
147
   default:
269
                ptr_rxd_buffer = 0; // reset rxd buffer
148
          UartState = 0;
270
                rxd_buffer_locked = FALSE; // unlock rxd buffer
149
          break;
271
        }
150
  }
272
 
151
}
273
}
152
 
274
 
153
 
275
 
154
// --------------------------------------------------------------------------
276
// --------------------------------------------------------------------------
155
void AddCRC(unsigned int wieviele)
277
void AddCRC(uint16_t datalen)
156
{
278
{
157
 unsigned int tmpCRC = 0,i;
279
        uint16_t tmpCRC = 0, i;
158
 for(i = 0; i < wieviele;i++)
280
        for(i = 0; i < datalen; i++)
Line 159... Line 281...
159
  {
281
        {
160
   tmpCRC += SendeBuffer[i];
282
                tmpCRC += txd_buffer[i];
161
  }
283
        }
162
   tmpCRC %= 4096;
284
        tmpCRC %= 4096;
163
   SendeBuffer[i++] = '=' + tmpCRC / 64;
285
        txd_buffer[i++] = '=' + tmpCRC / 64;
164
   SendeBuffer[i++] = '=' + tmpCRC % 64;
286
        txd_buffer[i++] = '=' + tmpCRC % 64;
165
   SendeBuffer[i++] = '\r';
287
        txd_buffer[i++] = '\r';
166
  UebertragungAbgeschlossen = 0;
288
        txd_complete = FALSE;
167
  UDR = SendeBuffer[0];
289
        UDR0 = txd_buffer[0]; // initiates the transmittion (continued in the TXD ISR)
168
}
290
}
169
 
291
 
170
 
292
 
171
 
293
 
172
// --------------------------------------------------------------------------
294
// --------------------------------------------------------------------------
173
void SendOutData(unsigned char cmd,unsigned char modul, unsigned char *snd, unsigned char len)
295
void SendOutData(uint8_t cmd,uint8_t module, uint8_t *snd, uint8_t len)
174
{
296
{
175
 unsigned int pt = 0;
297
        uint16_t pt = 0;
176
 unsigned char a,b,c;
298
        uint8_t a,b,c;
177
 unsigned char ptr = 0;
299
        uint8_t ptr = 0;
178
 
300
 
179
 SendeBuffer[pt++] = '#';               // Startzeichen
301
        txd_buffer[pt++] = '#';         // Start character
180
 SendeBuffer[pt++] = modul;             // Adresse (a=0; b=1,...)
302
        txd_buffer[pt++] = module;      // Address (a=0; b=1,...)
181
 SendeBuffer[pt++] = cmd;                       // Commando
303
        txd_buffer[pt++] = cmd;         // Command
Line 182... Line 304...
182
 
304
 
183
 while(len)
305
        while(len)
184
  {
306
        {
185
   if(len) { a = snd[ptr++]; len--;} else a = 0;
307
                if(len) { a = snd[ptr++]; len--;} else a = 0;
186
   if(len) { b = snd[ptr++]; len--;} else b = 0;
308
                if(len) { b = snd[ptr++]; len--;} else b = 0;
187
   if(len) { c = snd[ptr++]; len--;} else c = 0;
309
                if(len) { c = snd[ptr++]; len--;} else c = 0;
188
   SendeBuffer[pt++] = '=' + (a >> 2);
310
                txd_buffer[pt++] = '=' + (a >> 2);
189
   SendeBuffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
311
                txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
190
   SendeBuffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
312
                txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
191
   SendeBuffer[pt++] = '=' + ( c & 0x3f);
313
                txd_buffer[pt++] = '=' + ( c & 0x3f);
192
  }
314
        }
193
 AddCRC(pt);
315
        AddCRC(pt); // add checksum after data block and initates the transmission
194
}
316
}
195
 
317
 
196
 
318
 
197
// --------------------------------------------------------------------------
319
// --------------------------------------------------------------------------
198
void Decode64(unsigned char *ptrOut, unsigned char len, unsigned char ptrIn,unsigned char max)  // Wohin mit den Daten; Wie lang; Wo im RxdBuffer
320
void Decode64(uint8_t *ptrOut, uint8_t len, uint8_t ptrIn, uint8_t max)
199
{
321
{
200
 unsigned char a,b,c,d;
322
        uint8_t a,b,c,d;
201
 unsigned char ptr = 0;
323
        uint8_t ptr = 0;
202
 unsigned char x,y,z;
324
        uint8_t x,y,z;
203
 while(len)
325
        while(len)
204
  {
-
 
205
   a = RxdBuffer[ptrIn++] - '=';
326
        {
Line -... Line 327...
-
 
327
                a = rxd_buffer[ptrIn++] - '=';
206
   b = RxdBuffer[ptrIn++] - '=';
328
                b = rxd_buffer[ptrIn++] - '=';
207
   c = RxdBuffer[ptrIn++] - '=';
329
                c = rxd_buffer[ptrIn++] - '=';
208
   d = RxdBuffer[ptrIn++] - '=';
330
                d = rxd_buffer[ptrIn++] - '=';
-
 
331
                if(ptrIn > max - 2) break;
209
   if(ptrIn > max - 2) break;     // nicht mehr Daten verarbeiten, als empfangen wurden
332
 
Line 210... Line 333...
210
 
333
                x = (a << 2) | (b >> 4);
211
   x = (a << 2) | (b >> 4);
334
                y = ((b & 0x0f) << 4) | (c >> 2);
212
   y = ((b & 0x0f) << 4) | (c >> 2);
335
                z = ((c & 0x03) << 6) | d;
213
   z = ((c & 0x03) << 6) | d;
336
 
214
 
-
 
215
   if(len--) ptrOut[ptr++] = x; else break;
-
 
216
   if(len--) ptrOut[ptr++] = y; else break;
-
 
-
 
337
                if(len--) ptrOut[ptr++] = x; else break;
-
 
338
                if(len--) ptrOut[ptr++] = y; else break;
217
   if(len--) ptrOut[ptr++] = z; else break;
339
                if(len--) ptrOut[ptr++] = z; else break;
218
  }
340
        }
-
 
341
}
219
 
342
 
220
}
343
 
221
 
344
// --------------------------------------------------------------------------
222
// --------------------------------------------------------------------------
345
void USART0_ProcessRxData(void)
223
void BearbeiteRxDaten(void)
346
{
-
 
347
        // if data in the rxd buffer are not locked immediately return
224
{
348
        if(!rxd_buffer_locked) return;
225
 if(!NeuerDatensatzEmpfangen) return;
349
 
226
 
350
        #if  !defined (USE_KILLAGREG)  && !defined (USE_NAVICTRL)
227
 unsigned int tmp_int_arr1[1];
351
        uint16_t tmp_int_arr1[1]; // local int buffer
228
// unsigned int tmp_int_arr2[2];
352
        #endif
229
// unsigned int tmp_int_arr3[3];
353
        uint8_t tmp_char_arr2[2]; // local char buffer
230
 unsigned char tmp_char_arr2[2];
354
 
231
// unsigned char tmp_char_arr3[3];
355
 
232
// unsigned char tmp_char_arr4[4];
356
        switch(rxd_buffer[2])
233
 //if(!MotorenEin) 
357
        {
234
  switch(RxdBuffer[2])
358
                #if  !defined (USE_KILLAGREG)  && !defined (USE_NAVICTRL)
235
  {
359
                case 'K':// Compass value
236
   case 'K':// Kompasswert
360
                        Decode64((uint8_t *) &tmp_int_arr1[0], sizeof(tmp_int_arr1), 3, ReceivedBytes);
237
            Decode64((unsigned char *) &tmp_int_arr1[0],sizeof(tmp_int_arr1),3,AnzahlEmpfangsBytes);
361
                        CompassHeading = tmp_int_arr1[0];
238
            KompassValue = tmp_int_arr1[0];
362
                        CompassOffCourse = ((540 + CompassHeading - CompassCourse) % 360) - 180;
239
            KompassRichtung = ((540 + KompassValue - KompassStartwert) % 360) - 180;
363
                        break;
240
                        break;
364
                #endif
241
   case 'a':// Texte der Analogwerte
365
                case 'a':// Labels of the Analog Debug outputs
242
            Decode64((unsigned char *) &tmp_char_arr2[0],sizeof(tmp_char_arr2),3,AnzahlEmpfangsBytes);
366
                        Decode64((uint8_t *) &tmp_char_arr2[0], sizeof(tmp_char_arr2), 3, ReceivedBytes);
243
            DebugTextAnforderung = tmp_char_arr2[0];
367
                        RequestDebugLabel = tmp_char_arr2[0];
244
            PcZugriff = 255;
368
                        PcAccess = 255;
-
 
369
                        break;
245
                        break;
370
                case 'b': // extern control
246
   case 'b':
371
                        Decode64((uint8_t *) &ExternControl,sizeof(ExternControl), 3, ReceivedBytes);
247
                        Decode64((unsigned char *) &ExternControl,sizeof(ExternControl),3,AnzahlEmpfangsBytes);
372
                        RemoteButtons |= ExternControl.RemoteButtons;
248
                        RemoteTasten |= ExternControl.RemoteTasten;
373
                        ConfirmFrame = ExternControl.Frame;
249
            ConfirmFrame = ExternControl.Frame;
374
                        break;
250
            break;
375
                case 'c': // extern control with debug request
251
   case 'c':
376
                        Decode64((uint8_t *) &ExternControl,sizeof(ExternControl),3,ReceivedBytes);
252
                        Decode64((unsigned char *) &ExternControl,sizeof(ExternControl),3,AnzahlEmpfangsBytes);
377
                        RemoteButtons |= ExternControl.RemoteButtons;
253
                        RemoteTasten |= ExternControl.RemoteTasten;
378
                        ConfirmFrame = ExternControl.Frame;
254
            ConfirmFrame = ExternControl.Frame;
379
                        RequestDebugData = TRUE;
255
            DebugDataAnforderung = 1;
380
                        PcAccess = 255;
256
            PcZugriff = 255;
381
                        break;
257
            break;
382
                case 'h':// x-1 display columns
258
   case 'h':// x-1 Displayzeilen
383
                        Decode64((uint8_t *) &tmp_char_arr2[0],sizeof(tmp_char_arr2),3,ReceivedBytes);
259
            Decode64((unsigned char *) &tmp_char_arr2[0],sizeof(tmp_char_arr2),3,AnzahlEmpfangsBytes);
384
                        RemoteButtons |= tmp_char_arr2[0];
260
            RemoteTasten |= tmp_char_arr2[0];
-
 
261
                        if(tmp_char_arr2[1] == 255) NurKanalAnforderung = 1; else NurKanalAnforderung = 0; // keine Displaydaten
385
                        if(tmp_char_arr2[1] == 255) RequestChannelOnly = TRUE;
262
                        DebugDisplayAnforderung = 1;
386
                        else RequestChannelOnly = FALSE; // keine Displaydaten
263
                        break;
387
                        RequestDisplay = TRUE;
264
   case 't':// Motortest
-
 
265
            Decode64((unsigned char *) &MotorTest[0],sizeof(MotorTest),3,AnzahlEmpfangsBytes);
388
                        break;
266
            PcZugriff = 255;
389
                case 't':// motor test
267
                        break;
390
                        Decode64((uint8_t *) &MotorTest[0],sizeof(MotorTest),3,ReceivedBytes);
268
   case 'k':// Keys von DubWise
391
                        PcAccess = 255;
269
            Decode64((unsigned char *) &DubWiseKeys[0],sizeof(DubWiseKeys),3,AnzahlEmpfangsBytes);
392
                        break;
-
 
393
                case 'k':// keys from DubWise
270
                        ConfirmFrame = DubWiseKeys[3];
394
                        Decode64((uint8_t *) &DubWiseKeys[0],sizeof(DubWiseKeys),3,ReceivedBytes);
271
            PcZugriff = 255;
395
                        ConfirmFrame = DubWiseKeys[3];
272
                        break;
396
                        PcAccess = 255;
273
   case 'v': // Version-Anforderung     und Ausbaustufe
397
                        break;
274
            GetVersionAnforderung = 1;
398
                case 'v': // get version and board release
275
            break;                                                               
399
                        RequestVerInfo = TRUE;
276
   case 'g':// "Get"-Anforderung für Debug-Daten 
400
                        break;
277
            // Bei Get werden die vom PC einstellbaren Werte vom PC zurückgelesen
401
                case 'g':// get external control data
278
            DebugGetAnforderung = 1;
402
                        RequestExternalControl = TRUE;
279
            break;
403
                        break;
280
   case 'q':// "Get"-Anforderung für Settings
404
                case 'q':// get settings
281
            // Bei Get werden die vom PC einstellbaren Werte vom PC zurückgelesen
405
                        Decode64((uint8_t *) &tmp_char_arr2[0],sizeof(tmp_char_arr2),3,ReceivedBytes);
282
            Decode64((unsigned char *) &tmp_char_arr2[0],sizeof(tmp_char_arr2),3,AnzahlEmpfangsBytes);
406
                        while(!txd_complete);
283
            while(!UebertragungAbgeschlossen);
407
                        if(tmp_char_arr2[0] != 0xff)
284
            if(tmp_char_arr2[0] != 0xff)
-
 
285
             {
408
                        {
286
                          if(tmp_char_arr2[0] > 5) tmp_char_arr2[0] = 5;
409
                                if(tmp_char_arr2[0] > 5) tmp_char_arr2[0] = 5; // limit to 5
287
                  ReadParameterSet(tmp_char_arr2[0], (unsigned char *) &EE_Parameter.Kanalbelegung[0], STRUCT_PARAM_LAENGE);                   
410
                                // load requested parameter set
288
                  SendOutData('L' + tmp_char_arr2[0] -1,MeineSlaveAdresse,(unsigned char *) &EE_Parameter.Kanalbelegung[0],STRUCT_PARAM_LAENGE);
411
                                ParamSet_ReadFromEEProm(tmp_char_arr2[0]);
289
             }
412
                                SendOutData('L' + tmp_char_arr2[0] -1,MySlaveAddr,(uint8_t *) &ParamSet.ChannelAssignment[0],PARAMSET_STRUCT_LEN);
290
             else
413
                        }
291
                  SendOutData('L' + GetActiveParamSetNumber()-1,MeineSlaveAdresse,(unsigned char *) &EE_Parameter.Kanalbelegung[0],STRUCT_PARAM_LAENGE);
414
                        else // send active parameter set
292
             
415
                        SendOutData('L' + GetParamByte(PID_ACTIVE_SET)-1,MySlaveAddr,(uint8_t *) &ParamSet.ChannelAssignment[0],PARAMSET_STRUCT_LEN);
293
            break;
416
 
294
       
417
                        break;
295
   case 'l':
418
 
Line 296... Line 419...
296
   case 'm':
419
                case 'l':
297
   case 'n':
420
                case 'm':
298
   case 'o':
421
                case 'n':
299
   case 'p': // Parametersatz speichern
422
                case 'o':
300
            Decode64((unsigned char *) &EE_Parameter.Kanalbelegung[0],STRUCT_PARAM_LAENGE,3,AnzahlEmpfangsBytes);
423
                case 'p': // save parameterset
301
                        WriteParameterSet(RxdBuffer[2] - 'l' + 1, (unsigned char *) &EE_Parameter.Kanalbelegung[0], STRUCT_PARAM_LAENGE);
424
                        Decode64((uint8_t *) &ParamSet.ChannelAssignment[0],PARAMSET_STRUCT_LEN,3,ReceivedBytes);
302
            eeprom_write_byte(&EEPromArray[EEPROM_ADR_ACTIVE_SET], RxdBuffer[2] - 'l' + 1);  // aktiven Datensatz merken
425
                        ParamSet_WriteToEEProm(rxd_buffer[2] - 'l' + 1);
303
            Umschlag180Nick = (long) EE_Parameter.WinkelUmschlagNick * 2500L;
426
                        TurnOver180Pitch = (int32_t) ParamSet.AngleTurnOverPitch * 2500L;
304
            Umschlag180Roll = (long) EE_Parameter.WinkelUmschlagRoll * 2500L;
427
                        TurnOver180Roll = (int32_t) ParamSet.AngleTurnOverRoll * 2500L;
305
            Piep(GetActiveParamSetNumber());
428
                        Beep(GetActiveParamSet());
306
         break;
429
                        break;
307
               
-
 
308
         
430
 
309
  }
431
 
Line 310... Line -...
310
// DebugOut.AnzahlZyklen =  Debug_Timer_Intervall;
-
 
311
 NeuerDatensatzEmpfangen = 0;
-
 
312
}
-
 
313
 
-
 
314
//############################################################################
-
 
315
//Routine für die Serielle Ausgabe
-
 
316
int uart_putchar (char c)
-
 
Line 317... Line 432...
317
//############################################################################
432
        }
318
{
-
 
319
        if (c == '\n')
433
        // unlock the rxd buffer after processing
320
                uart_putchar('\r');
-
 
321
        //Warten solange bis Zeichen gesendet wurde
434
        rxd_buffer_locked = FALSE;
322
        loop_until_bit_is_set(USR, UDRE);
435
}
Line 323... Line -...
323
        //Ausgabe des Zeichens
-
 
324
        UDR = c;
436
 
325
       
437
//############################################################################
326
        return (0);
438
//Routine für die Serielle Ausgabe
327
}
-
 
328
 
439
int16_t uart_putchar (int8_t c)
329
// --------------------------------------------------------------------------
440
//############################################################################
330
void WriteProgramData(unsigned int pos, unsigned char wert)
441
{
331
{
442
        if (c == '\n')
332
  //if (ProgramLocation == IN_RAM) Buffer[pos] = wert;
443
                uart_putchar('\r');
333
  // else eeprom_write_byte(&EE_Buffer[pos], wert);
444
        // wait until previous character was send
-
 
445
        loop_until_bit_is_set(UCSR0A, UDRE0);
-
 
446
        //Ausgabe des Zeichens
334
  // Buffer[pos] = wert;
447
        UDR0 = c;
335
}
448
        return (0);
336
 
449
}
-
 
450
 
-
 
451
 
337
//############################################################################
452
//---------------------------------------------------------------------------------------------
338
//INstallation der Seriellen Schnittstelle
453
void USART0_TransmitTxData(void)
339
void UART_Init (void)
454
{
-
 
455
        if(!txd_complete) return;
Line 340... Line 456...
340
//############################################################################
456
 
341
{
-
 
342
        //Enable TXEN im Register UCR TX-Data Enable & RX Enable
457
        if(RequestExternalControl && txd_complete)            // Bei Get werden die vom PC einstellbaren Werte vom PC zurückgelesen
-
 
458
        {
343
 
459
                SendOutData('G',MySlaveAddr,(uint8_t *) &ExternControl,sizeof(ExternControl));
-
 
460
                RequestExternalControl = FALSE;
-
 
461
        }
Line 344... Line -...
344
        UCR=(1 << TXEN) | (1 << RXEN);
-
 
345
    // UART Double Speed (U2X)
-
 
346
        USR   |= (1<<U2X);          
-
 
347
        // RX-Interrupt Freigabe
-
 
348
        UCSRB |= (1<<RXCIE);          
-
 
349
        // TX-Interrupt Freigabe
-
 
350
        UCSRB |= (1<<TXCIE);          
-
 
351
 
-
 
352
        //Teiler wird gesetzt 
-
 
353
        UBRR=(SYSCLK / (BAUD_RATE * 8L) - 1);
-
 
354
        //UBRR = 33;
-
 
355
        //öffnet einen Kanal für printf (STDOUT)
-
 
356
        //fdevopen (uart_putchar, 0);
-
 
357
        //sbi(PORTD,4);
-
 
358
  Debug_Timer = SetDelay(200);  
-
 
359
  Kompass_Timer = SetDelay(220);  
-
 
360
}
-
 
361
 
-
 
362
//---------------------------------------------------------------------------------------------
-
 
363
void DatenUebertragung(void)  
-
 
364
{
-
 
365
 if(!UebertragungAbgeschlossen) return;
-
 
366
 
-
 
367
   if(DebugGetAnforderung && UebertragungAbgeschlossen)               // Bei Get werden die vom PC einstellbaren Werte vom PC zurückgelesen
462
 
368
   {
463
        #if  !defined (USE_KILLAGREG)  && !defined (USE_NAVICTRL)
369
      SendOutData('G',MeineSlaveAdresse,(unsigned char *) &ExternControl,sizeof(ExternControl));
464
    if((CheckDelay(Compass_Timer)) && txd_complete)
370
          DebugGetAnforderung = 0;
465
        {
371
   }
466
                ToMk3Mag.Attitude[0] = (int16_t) (IntegralPitch / 108);  // approx. 0,1 Deg
372
 
467
                ToMk3Mag.Attitude[1] = (int16_t) (IntegralRoll / 108);   // approx. 0,1 Deg
373
    if((CheckDelay(Kompass_Timer)) && UebertragungAbgeschlossen)        
468
                ToMk3Mag.UserParam[0] = FCParam.UserParam1;
374
         {
469
                ToMk3Mag.UserParam[1] = FCParam.UserParam2;
375
                  WinkelOut.Winkel[0] = (int) (IntegralNick / 108);  // etwa in 0,1 Grad
470
                ToMk3Mag.CalState = CompassCalState;
376
                  WinkelOut.Winkel[1] = (int) (IntegralRoll / 108);  // etwa in 0,1 Grad
471
                SendOutData('w',MySlaveAddr,(uint8_t *) &ToMk3Mag,sizeof(ToMk3Mag));
377
                  WinkelOut.UserParameter[0] = Parameter_UserParam1;
472
                // the last state is 5 and should be send only once to avoid multiple flash writing
378
                  WinkelOut.UserParameter[1] = Parameter_UserParam2;
473
                if(CompassCalState > 4)  CompassCalState = 0;
379
          SendOutData('w',MeineSlaveAdresse,(unsigned char *) &WinkelOut,sizeof(WinkelOut));
474
                Compass_Timer = SetDelay(99);
380
          if(WinkelOut.CalcState > 4)  WinkelOut.CalcState = 6; // wird dann in SPI auf Null gesetzt
475
        }
381
          Kompass_Timer = SetDelay(99);  
476
        #endif
382
         }
477
 
383
 
478
    if((CheckDelay(Debug_Timer) || RequestDebugData) && txd_complete)
384
    if((CheckDelay(Debug_Timer) || DebugDataAnforderung) && UebertragungAbgeschlossen)  
479
    {
385
         {
480
          SendOutData('D',MySlaveAddr,(uint8_t *) &DebugOut,sizeof(DebugOut));
386
          SendOutData('D',MeineSlaveAdresse,(unsigned char *) &DebugOut,sizeof(DebugOut));
481
          RequestDebugData = FALSE;
387
          DebugDataAnforderung = 0;
482
          Debug_Timer = SetDelay(MIN_DEBUG_INTERVALL);
388
          Debug_Timer = SetDelay(MIN_DEBUG_INTERVALL);  
483
    }
389
         }
484
 
390
    if(DebugTextAnforderung != 255) // Texte für die Analogdaten
485
    if(RequestDebugLabel != 255) // Texte für die Analogdaten
391
     {
486
     {
392
      SendOutData('A',DebugTextAnforderung + '0',(unsigned char *) ANALOG_TEXT[DebugTextAnforderung],16);
487
      SendOutData('A',RequestDebugLabel + '0',(uint8_t *) ANALOG_LABEL[RequestDebugLabel],16);
393
      DebugTextAnforderung = 255;
488
      RequestDebugLabel = 255;
394
         }
489
         }
395
     if(ConfirmFrame && UebertragungAbgeschlossen)   // Datensatz ohne CRC bestätigen 
490
     if(ConfirmFrame && txd_complete)   // Datensatz ohne CRC bestätigen
396
         {
491
         {
Line 397... Line 492...
397
      SendeBuffer[0] = '#';
492
      txd_buffer[0] = '#';