Subversion Repositories NaviCtrl

Rev

Rev 49 | Rev 112 | Go to most recent revision | Show entire file | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed

Rev 49 Rev 110
Line 52... Line 52...
52
// +  INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
52
// +  INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
53
// +  CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
53
// +  CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
54
// +  ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
54
// +  ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
55
// +  POSSIBILITY OF SUCH DAMAGE.
55
// +  POSSIBILITY OF SUCH DAMAGE.
56
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
56
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
-
 
57
#include <stdio.h>
-
 
58
#include <stdarg.h>
57
#include "91x_lib.h"
59
#include "91x_lib.h"
-
 
60
#include "main.h"
58
#include "uart0.h"
61
#include "uart0.h"
59
#include "uart1.h"
62
#include "uart1.h"
-
 
63
#include "timer.h"
60
#include "ubx.h"
64
#include "ubx.h"
61
#include <stdio.h>
65
#include "mkprotocol.h"
62
#include <stdarg.h>
-
 
Line -... Line 66...
-
 
66
 
-
 
67
u8 UART0_Request_VersionInfo    = FALSE;
-
 
68
u8 UART0_Request_NaviData               = FALSE;
-
 
69
u32 UART0_NaviData_Timer;
63
 
70
u32 UART0_NaviData_Interval = 0;        // in ms
64
//------------------------------------------------------------------------------------
71
//------------------------------------------------------------------------------------
Line 65... Line -...
65
// global variables
-
 
-
 
72
// global variables
66
 
73
 
67
 
-
 
68
// UART0 MUXER
74
#define UART0_BAUD_RATE 57600           //Baud Rate for the serial interfaces
69
 
75
// UART0 MUXER
70
UART0_MuxerState_t UART0_Muxer = UART0_UNDEF;
76
UART0_MuxerState_t UART0_Muxer = UART0_UNDEF;
-
 
77
u16 Uart0Baudrate = UART0_BAUD_RATE;
-
 
78
u16 Uart0MK3MagBaudrate = UART0_BAUD_RATE;
-
 
79
 
-
 
80
// the tx buffer
-
 
81
#define UART0_TX_BUFFER_LEN  150
-
 
82
u8 UART0_tbuffer[UART0_TX_BUFFER_LEN];
-
 
83
Buffer_t UART0_tx_buffer;
-
 
84
 
-
 
85
// the rx buffer
-
 
86
#define UART0_RX_BUFFER_LEN  150
Line 71... Line -...
71
u16 Uart0Baudrate = BAUD_RATE;
-
 
72
u16 Uart0MK3MagBaudrate = BAUD_RATE;
-
 
73
 
-
 
Line 74... Line 87...
74
volatile u8 txd_buffer0[TXD_BUFFER_LEN];
87
u8 UART0_rbuffer[UART0_RX_BUFFER_LEN];
75
volatile u8 txd_complete0 = TRUE;
88
Buffer_t UART0_rx_buffer;
Line 76... Line 89...
76
static u16 ptr_txd_buffer0 = 0;
89
 
Line 180... Line 193...
180
/********************************************************/
193
/********************************************************/
181
void UART0_Init(void)
194
void UART0_Init(void)
182
{
195
{
183
    UART_InitTypeDef UART_InitStructure;
196
    UART_InitTypeDef UART_InitStructure;
Line 184... Line 197...
184
       
197
       
Line 185... Line 198...
185
        SerialPutString("\r\n UART0 init...");
198
        UART1_PutString("\r\n UART0 init...");
Line 186... Line 199...
186
 
199
 
Line 187... Line 200...
187
        SCU_APBPeriphClockConfig(__UART0, ENABLE);  // Enable the UART0 Clock
200
        SCU_APBPeriphClockConfig(__UART0, ENABLE);  // Enable the UART0 Clock
188
 
201
 
189
        Uart0Baudrate = BAUD_RATE + ((BAUD_RATE * 2)/100);   // MK3Mag baudrate is a litlle bit higher...
202
        Uart0Baudrate = UART0_BAUD_RATE + ((UART0_BAUD_RATE * 2)/100);   // MK3Mag baudrate is a litlle bit higher...
190
 
203
 
Line 217... Line 230...
217
        // configure the uart 0 interupt line as an IRQ with priority 10 (0 is highest)
230
        // configure the uart 0 interupt line as an IRQ with priority 10 (0 is highest)
218
        VIC_Config(UART0_ITLine, VIC_IRQ, 10);
231
        VIC_Config(UART0_ITLine, VIC_IRQ, 10);
219
        // enable the uart 0 IRQ
232
        // enable the uart 0 IRQ
220
        VIC_ITCmd(UART0_ITLine, ENABLE);
233
        VIC_ITCmd(UART0_ITLine, ENABLE);
221
        UART0_Connect_to_MKGPS();
234
        UART0_Connect_to_MKGPS();
222
        SerialPutString("ok");
-
 
223
}
-
 
Line 224... Line 235...
224
 
235
 
225
/**************************************************************/
236
        // initialize txd buffer
226
/*         Transmit tx buffer via debug uart                  */
237
        UART0_tx_buffer.pData = UART0_tbuffer;
227
/**************************************************************/
238
        UART0_tx_buffer.Size = UART0_TX_BUFFER_LEN;
228
void UART0_Transmit(void)
-
 
229
{
-
 
230
        u8 tmp_tx;
239
        UART0_tx_buffer.Position = 0;
231
        // if something has to be send and the txd fifo is not full
-
 
232
        if((!txd_complete0) && (UART_GetFlagStatus(UART0, UART_FLAG_TxFIFOFull) == RESET))
240
        UART0_tx_buffer.Locked = FALSE;
233
        {
-
 
234
                tmp_tx = txd_buffer0[ptr_txd_buffer0]; // read byte from txd buffer
241
       
235
                // if terminating character or end of txd buffer reached
-
 
236
                if((tmp_tx == '\r') || (ptr_txd_buffer0 == TXD_BUFFER_LEN))
-
 
237
                {
242
        // initialize rxd buffer
238
                        ptr_txd_buffer0 = 0;    // reset txd buffer pointer
243
        UART0_rx_buffer.pData = UART0_rbuffer;
239
                        txd_complete0 = TRUE;// set complete flag
-
 
240
                }
-
 
241
                UART_SendData(UART0, tmp_tx); // put character to txd fifo
244
        UART0_rx_buffer.Size = UART0_RX_BUFFER_LEN;
242
                // set pointer to next byte
245
        UART0_rx_buffer.Position = 0;
243
                ptr_txd_buffer0++;
-
 
244
        }
-
 
Line 245... Line -...
245
}
-
 
246
 
-
 
247
/**************************************************************/
-
 
248
/* Add CRC and initiate transmission via debug uart           */
-
 
249
/**************************************************************/
-
 
250
void AddCRC0(u16 datalen)
-
 
251
{
-
 
252
        u16 tmpCRC = 0, i;
-
 
253
        for(i = 0; i < datalen; i++)
-
 
254
        {
-
 
255
                tmpCRC += txd_buffer0[i];
-
 
256
        }
-
 
257
        tmpCRC %= 4096;
-
 
258
        txd_buffer0[i++] = '=' + tmpCRC / 64;
-
 
259
        txd_buffer0[i++] = '=' + tmpCRC % 64;
-
 
260
        txd_buffer0[i++] = '\r';
-
 
261
 
246
        UART0_rx_buffer.Locked = FALSE;
262
        ptr_txd_buffer0 = 0;
-
 
263
        txd_complete0 = FALSE;
247
 
Line 264... Line -...
264
        UART_SendData(UART0, txd_buffer0[ptr_txd_buffer0++]);   // send first byte, to be continued in the txd irq
-
 
265
}
-
 
266
 
-
 
267
 
-
 
268
 
-
 
269
/**************************************************************/
-
 
270
/* Code output data                                           */
-
 
271
/**************************************************************/
-
 
272
void SendOutData0(u8 cmd, u8 Address, u8 numofbuffers , ...) //u8 *data, u8 len, ....
-
 
273
{
-
 
274
        va_list ap;
-
 
275
 
-
 
276
        u16 pt = 0;
-
 
277
        u8 a,b,c;
-
 
278
        u8 ptr = 0;
-
 
279
 
-
 
280
        u8* pdata = NULL;
-
 
281
        int len = 0;
-
 
282
 
-
 
283
        txd_buffer0[pt++] = '#';                                // Start character
-
 
284
        txd_buffer0[pt++] = 'a' + Address;      // Address (a=0; b=1,...)
-
 
285
        txd_buffer0[pt++] = cmd;                                // Command
-
 
286
 
-
 
287
        va_start(ap, numofbuffers);
-
 
288
        if(numofbuffers)
-
 
289
        {
-
 
290
                pdata = va_arg(ap, u8*);
-
 
291
                len = va_arg(ap, int);
-
 
292
                ptr = 0;
-
 
293
                numofbuffers--;
-
 
294
        }
-
 
295
        while(len)
-
 
296
        {
-
 
297
                if(len)
-
 
298
                {
-
 
299
                        a = pdata[ptr++];
-
 
300
                        len--;
-
 
301
                        if((!len) && numofbuffers) // try to jump to next buffer
-
 
302
                        {
-
 
303
                                pdata = va_arg(ap, u8*);
-
 
304
                                len = va_arg(ap, int);
-
 
305
                                ptr = 0;
-
 
306
                                numofbuffers--;
-
 
307
                        }
-
 
308
                }
-
 
309
                else a = 0;
-
 
310
                if(len)
-
 
311
                {
-
 
312
                        b = pdata[ptr++];
-
 
313
                        len--;
-
 
314
                        if((!len) && numofbuffers) // try to jump to next buffer
-
 
315
                        {
-
 
316
                                pdata = va_arg(ap, u8*);
-
 
317
                                len = va_arg(ap, int);
-
 
318
                                ptr = 0;
-
 
319
                                numofbuffers--;
-
 
320
                        }
-
 
321
                }
-
 
322
                else b = 0;
-
 
323
                if(len)
-
 
324
                {
-
 
325
                        c = pdata[ptr++];
-
 
326
                        len--;
-
 
327
                        if((!len) && numofbuffers) // try to jump to next buffer
-
 
328
                        {
-
 
329
                                pdata = va_arg(ap, u8*);
-
 
330
                                len = va_arg(ap, int);
-
 
331
                                ptr = 0;
-
 
332
                                numofbuffers--;
-
 
333
                        }
-
 
334
                }
-
 
335
                else c = 0;
-
 
336
                txd_buffer0[pt++] = '=' + (a >> 2);
-
 
337
                txd_buffer0[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
-
 
338
                txd_buffer0[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
-
 
339
                txd_buffer0[pt++] = '=' + ( c & 0x3f);
-
 
340
        }
-
 
341
        va_end(ap);
-
 
342
        AddCRC0(pt);    // add checksum after data block and initates the transmission
-
 
343
}
248
        UART1_PutString("ok");
344
 
249
}
345
 
250
 
346
/********************************************************/
251
/********************************************************/
347
/*            UART0 Interrupt Handler                   */
252
/*            UART0 Interrupt Handler                   */
348
/********************************************************/
253
/********************************************************/
349
void UART0_IRQHandler(void)
-
 
350
{
-
 
351
        u8 c;
-
 
352
        /*
-
 
353
        static u8 frame_error_cnt = 0;
-
 
354
       
-
 
355
    // use frame error to adjust baudrate for MK3MAG
-
 
356
        if((UART_GetITStatus(UART0, UART_IT_FrameError) == SET))
-
 
357
        {
-
 
358
           u8 msg[20];
-
 
359
           frame_error_cnt++;
-
 
360
         
-
 
361
           if (frame_error_cnt == 200)
-
 
362
           {
-
 
363
            frame_error_cnt = 0;
-
 
364
            VIC_ITCmd(UART0_ITLine, DISABLE);
-
 
365
           
-
 
366
            Uart0MK3MagBaudrate +=100;
-
 
367
            if (Uart0MK3MagBaudrate > (BAUD_RATE+1000)) Uart0MK3MagBaudrate = BAUD_RATE;
-
 
368
           
-
 
369
            Uart0Baudrate = Uart0MK3MagBaudrate;
-
 
370
           
-
 
371
            SerialPutString(" adjusting UART0 baudrate to");
-
 
372
            sprintf(msg, " %d baud...", Uart0MK3MagBaudrate); SerialPutString(msg);
-
 
373
           
-
 
374
                while(UART_GetFlagStatus(UART0, UART_FLAG_RxFIFOEmpty) != SET)
-
 
375
                        {
-
 
376
                                c =  UART_ReceiveData(UART0);
-
 
377
                        }
-
 
378
       
-
 
379
            UART_ClearITPendingBit(UART0, UART_IT_FrameError);                  // clear frame error interrupt flag
-
 
380
           
-
 
381
            UART0_Init();
-
 
382
            return;
-
 
383
         }
254
void UART0_IRQHandler(void)
384
 
255
{
385
        }*/
256
        u8 c;
386
        // if receive irq or receive timeout irq has occured
257
        // if receive irq or receive timeout irq has occured
387
        if((UART_GetITStatus(UART0, UART_IT_Receive) != RESET) || (UART_GetITStatus(UART0, UART_IT_ReceiveTimeOut) != RESET) )
258
        if((UART_GetITStatus(UART0, UART_IT_Receive) != RESET) || (UART_GetITStatus(UART0, UART_IT_ReceiveTimeOut) != RESET) )
Line 408... Line 279...
408
                                c = UART_ReceiveData(UART0); // get byte from rx fifo
279
                                c = UART_ReceiveData(UART0); // get byte from rx fifo
409
                                switch(UART0_Muxer)
280
                                switch(UART0_Muxer)
410
                                {
281
                                {
411
                                        case UART0_MKGPS:
282
                                        case UART0_MKGPS:
412
                                                UBX_Parser(c); // if connected to GPS forward byte to ubx parser
283
                                                UBX_Parser(c); // if connected to GPS forward byte to ubx parser
-
 
284
                                                MKProtocol_CollectSerialFrame(&UART0_rx_buffer, c);     // ckeck for MK-Frames also
413
                                                break;
285
                                                break;
414
                                        case UART0_MK3MAG:
286
                                        case UART0_MK3MAG:
415
                                                // ignore any byte send from MK3MAG
287
                                                // ignore any byte send from MK3MAG
416
                                                break;
288
                                                break;
417
                                        case UART0_UNDEF:
289
                                        case UART0_UNDEF:
Line 421... Line 293...
421
                                } // eof switch(UART0_Muxer)
293
                                } // eof switch(UART0_Muxer)
422
                        } // eof while
294
                        } // eof while
423
                }  // eof UART0 is not the DebugUART
295
                }  // eof UART0 is not the DebugUART
424
        } // eof receive irq or receive timeout irq
296
        } // eof receive irq or receive timeout irq
425
}
297
}
-
 
298
 
-
 
299
/**************************************************************/
-
 
300
/* Process incomming data from debug uart                     */
-
 
301
/**************************************************************/
-
 
302
void UART0_ProcessRxData(void)
-
 
303
{
-
 
304
        SerialMsg_t SerialMsg;
-
 
305
        // if data in the rxd buffer are not locked immediately return
-
 
306
        if((UART0_rx_buffer.Locked == FALSE) || (DebugUART == UART0) ) return;
-
 
307
       
-
 
308
        MKProtocol_DecodeSerialFrame(&UART0_rx_buffer, &SerialMsg); // decode serial frame in rxd buffer
-
 
309
 
-
 
310
        switch(SerialMsg.Address) // check for Slave Address
-
 
311
        {
-
 
312
                case NC_ADDRESS:  // own Slave Address
-
 
313
                switch(SerialMsg.CmdID)
-
 
314
                {
-
 
315
                        default:
-
 
316
                                break;
-
 
317
                } // case NC_ADDRESS
-
 
318
                // "break;" is missing here to fall thru to the common commands
-
 
319
 
-
 
320
                default:  // and any other Slave Address
-
 
321
 
-
 
322
                switch(SerialMsg.CmdID) // check CmdID
-
 
323
                {
-
 
324
                        case 'o': // request for navigation information
-
 
325
                                UART0_NaviData_Interval = (u32) SerialMsg.pData[0] * 10;
-
 
326
                                if(UART0_NaviData_Interval > 0) UART0_Request_NaviData = TRUE;
-
 
327
                                break;
-
 
328
 
-
 
329
                        case 'v': // request for version info
-
 
330
                                UART0_Request_VersionInfo = TRUE;
-
 
331
                                break;
-
 
332
                        default:
-
 
333
                                // unsupported command recieved
-
 
334
                                break;
-
 
335
                }
-
 
336
                break; // default:
-
 
337
        }
-
 
338
        // unlock the rxd buffer after processing
-
 
339
        UART0_rx_buffer.Position = 0;
-
 
340
        UART0_rx_buffer.Locked = FALSE;
-
 
341
}
-
 
342
 
-
 
343
/**************************************************************/
-
 
344
/*         Transmit tx buffer via uart0                       */
-
 
345
/**************************************************************/
-
 
346
void UART0_Transmit(void)
-
 
347
{
-
 
348
        u8 tmp_tx;
-
 
349
        if(DebugUART == UART0) return; // no data output if debug uart is rederected to UART0
-
 
350
        // if something has to be send and the txd fifo is not full
-
 
351
        if((UART0_tx_buffer.Locked == TRUE) && (UART_GetFlagStatus(UART0, UART_FLAG_TxFIFOFull) == RESET))
-
 
352
        {
-
 
353
                tmp_tx = UART0_tx_buffer.pData[UART0_tx_buffer.Position++]; // read next byte from txd buffer
-
 
354
                UART_SendData(UART0, tmp_tx); // put character to txd fifo
-
 
355
                // if terminating character or end of txd buffer reached
-
 
356
                if((tmp_tx == '\r') || (UART0_tx_buffer.Position == UART0_tx_buffer.Size))
-
 
357
                {
-
 
358
                        UART0_tx_buffer.Position = 0; // reset txd buffer positon
-
 
359
                        UART0_tx_buffer.Locked = FALSE;// unlock tx buffer
-
 
360
                }
-
 
361
        }
-
 
362
}
-
 
363
 
-
 
364
 
-
 
365
/**************************************************************/
-
 
366
/* Send the answers to incomming commands at the uart0        */
-
 
367
/**************************************************************/
-
 
368
void UART0_TransmitTxData(void)
-
 
369
{
-
 
370
        if(DebugUART == UART0) return;
-
 
371
        UART0_Transmit(); // output pending bytes in tx buffer
-
 
372
        if(UART0_tx_buffer.Locked == TRUE) return;
-
 
373
 
-
 
374
        if(( (UART0_NaviData_Interval && CheckDelay(UART0_NaviData_Timer) ) || UART0_Request_NaviData) && (UART0_tx_buffer.Locked == FALSE))
-
 
375
        {
-
 
376
                NaviData.Errorcode = ErrorCode;
-
 
377
                MKProtocol_CreateSerialFrame(&UART0_tx_buffer, 'O', NC_ADDRESS,1, (u8 *)&NaviData, sizeof(NaviData));
-
 
378
                UART0_NaviData_Timer = SetDelay(UART0_NaviData_Interval);
-
 
379
                UART0_Request_NaviData = FALSE;
-
 
380
        }      
-
 
381
        UART0_Transmit(); // output pending bytes in tx buffer
-
 
382
}