uart.c
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2011, Ascending Technologies GmbH
00003 Copyright (c) 2011, Markus Achtelik, ASL, ETH Zurich, Switzerland
00004 You can contact the author at <markus dot achtelik at mavt dot ethz dot ch>
00005 
00006 All rights reserved.
00007 
00008 Redistribution and use in source and binary forms, with or without
00009 modification, are permitted provided that the following conditions are met:
00010 * Redistributions of source code must retain the above copyright
00011 notice, this list of conditions and the following disclaimer.
00012 * Redistributions in binary form must reproduce the above copyright
00013 notice, this list of conditions and the following disclaimer in the
00014 documentation and/or other materials provided with the distribution.
00015 * Neither the name of ETHZ-ASL nor the
00016 names of its contributors may be used to endorse or promote products
00017 derived from this software without specific prior written permission.
00018 
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022 DISCLAIMED. IN NO EVENT SHALL ETHZ-ASL BE LIABLE FOR ANY
00023 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00024 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00026 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029 
00030 */
00031 
00032 #include <string.h>
00033 
00034 #include "LPC214x.h"
00035 #include "interrupt_utils.h"
00036 #include "system.h"
00037 #include "main.h"
00038 #include "uart.h"
00039 #include "irq.h"
00040 #include "hardware.h"
00041 #include "gpsmath.h"
00042 #include "ssp.h"
00043 #include "lpcUART.h"
00044 
00045 #include "HL_interface.h"
00046 
00047 volatile unsigned char transmission_running = 0;
00048 
00049 unsigned uart0_rx_cpsr;
00050 unsigned uart0_tx_cpsr;
00051 
00052 #define UART0_DISABLE_TX_INT uart0_tx_cpsr=disableIRQ();U0IER &= ~UIER_ETBEI;restoreIRQ(uart0_tx_cpsr);
00053 #define UART0_ENABLE_TX_INT  uart0_tx_cpsr=disableIRQ();U0IER |= UIER_ETBEI;restoreIRQ(uart0_tx_cpsr);
00054 #define UART0_DISABLE_RX_INT uart0_rx_cpsr=disableIRQ();U0IER &= ~UIER_ERBFI;restoreIRQ(uart0_rx_cpsr);
00055 #define UART0_ENABLE_RX_INT  uart0_rx_cpsr=disableIRQ();U0IER |= UIER_ERBFI;restoreIRQ(uart0_rx_cpsr);
00056 
00057 volatile short uart0_min_tx_buffer = UART0_TX_BUFFERSIZE;
00058 volatile short uart0_min_rx_buffer = UART0_RX_BUFFERSIZE;
00059 
00060 volatile uint8_t rxBuffer[UART0_RX_BUFFERSIZE];
00061 uint8_t rxParseBuffer[UART0_RX_BUFFERSIZE];
00062 Fifo rxFifo;
00063 
00064 volatile uint8_t txBuffer[UART0_TX_BUFFERSIZE];
00065 Fifo txFifo;
00066 
00067 volatile unsigned int UART_rxPacketCount = 0;
00068 volatile unsigned int UART_rxGoodPacketCount = 0;
00069 
00070 PacketInfo packetInfo[PACKET_INFO_SIZE];
00071 uint32_t registeredPacketCnt = 0;
00072 
00073 volatile char autobaud_in_progress = 0;
00074 
00075 void uart0ISR(void) __irq
00076 {
00077   uint8_t t;
00078   uint16_t iid;
00079   short freemem = 0;
00080 
00081   // Read IIR to clear interrupt and find out the cause
00082   while (((iid = U0IIR) & UIIR_NO_INT) == 0)
00083   {
00084     if (iid & 0x100)
00085     {
00086       autobaud_in_progress = 1;
00087       U0ACR |= 0x100; //clear ABEO interrupt
00088       U0ACR &= ~0x01; // disable autobaud
00089       U0IER &= ~((1 << 8) | (1 << 9)); //disable ABEO and ABTO interrupts
00090 
00091       autobaud_in_progress = 0;
00092     }
00093 
00094     if (iid & 0x200)
00095     {
00096       autobaud_in_progress = 1;
00097       U0ACR |= 0x200; //clear ABTO int
00098 
00099       autobaud_in_progress = 0;
00100     }
00101 
00102     switch (iid & UIIR_ID_MASK)
00103     {
00104       case UIIR_RLS_INT: // Receive Line Status
00105         U0LSR; // read LSR to clear
00106         break;
00107 
00108       case UIIR_CTI_INT: // <-- keep this together, in order to read remaining bytes below fifo threshold
00109       case UIIR_RDA_INT:
00110         // RDA interrupt
00111         //receive handler
00112         rxFifo.inUse = 1;
00113         do
00114         { // read from fifo as long as there is data available
00115           t = U0RBR;
00116           freemem = Fifo_availableMemory(&rxFifo);
00117           if (freemem < uart0_min_rx_buffer)
00118             uart0_min_rx_buffer = freemem;
00119           if (!Fifo_writeByte(&rxFifo, t))
00120             break;
00121         } while (U0LSR & ULSR_RDR);
00122         rxFifo.inUse = 0;
00123 
00124         break;
00125 
00126       case UIIR_THRE_INT:
00127         // THRE interrupt
00128         if(!(IOPIN0&(1<<CTS_RADIO))){
00129           txFifo.inUse = 1;
00130           while (U0LSR & ULSR_THRE)
00131           {
00132             if (Fifo_readByte(&txFifo, &t))
00133             {
00134               U0THR = t;
00135             }
00136             else
00137             {
00138               transmission_running = 0;
00139               break;
00140             }
00141           }
00142           txFifo.inUse = 0;
00143         }
00144         break;
00145 
00146       default: // Unknown
00147         U0LSR;
00148         U0RBR;
00149         break;
00150     }
00151   }
00152   VICVectAddr = 0; // Acknowledge Interrupt
00153 }
00154 
00155 void Fifo_initialize(Fifo * fifo, volatile uint8_t * buffer, uint32_t bufferSize)
00156 {
00157   fifo->buffer = buffer;
00158   fifo->bufferSize = bufferSize;
00159   fifo->readIdx = 0;
00160   fifo->writeIdx = 0;
00161   fifo->tmp = 0;
00162   fifo->mask = bufferSize - 1;
00163   fifo->inUse = 0;
00164 }
00165 
00166 uint8_t Fifo_writeByte(Fifo * fifo, uint8_t byte)
00167 {
00168   fifo->tmp = ((fifo->writeIdx + 1) & fifo->mask);
00169   if (fifo->readIdx == fifo->tmp)
00170     return 0;
00171   fifo->buffer[fifo->writeIdx] = byte;
00172   fifo->writeIdx = fifo->tmp;
00173   return 1;
00174 }
00175 
00176 uint8_t Fifo_writeBlock(Fifo * fifo, void *data, uint32_t length)
00177 {
00178   if (Fifo_availableMemory(fifo) <= length)
00179     return 0;
00180   uint8_t *ptr = (uint8_t *)data;
00181   while (length--)
00182   {
00183     fifo->buffer[fifo->writeIdx] = *ptr++;
00184     fifo->writeIdx = (fifo->writeIdx + 1) & fifo->mask;
00185   }
00186 
00187   //    //safe method
00188   //    int i=0;
00189   //    uint8_t *ptr = (uint8_t *)data;
00190   //    for(i=0; i<length; i++){
00191   //            if(!Fifo_writeByte(fifo, ptr[i]))
00192   //                    return 0;
00193   //    }
00194 
00195   return 1;
00196 }
00197 
00198 uint8_t Fifo_readByte(Fifo * fifo, uint8_t * byte)
00199 {
00200   if (fifo->readIdx == fifo->writeIdx)
00201     return 0;
00202   *byte = fifo->buffer[fifo->readIdx];
00203   fifo->readIdx = (fifo->readIdx + 1) & fifo->mask;
00204   return 1;
00205 }
00206 
00207 uint16_t Fifo_availableMemory(Fifo * fifo)
00208 {
00209   return (fifo->readIdx - fifo->writeIdx - 1) & fifo->mask;
00210 }
00211 
00212 void Fifo_reset(Fifo * fifo)
00213 {
00214   fifo->writeIdx = 0;
00215   fifo->readIdx = 0;
00216 }
00217 
00218 PacketInfo* registerPacket(uint8_t descriptor, void * data)
00219 {
00220   //    if(registeredPacketCnt < PACKET_INFO_SIZE){
00221   packetInfo[registeredPacketCnt].data = data;
00222   packetInfo[registeredPacketCnt].descriptor = descriptor;
00223   packetInfo[registeredPacketCnt].updated = 0;
00224   registeredPacketCnt++;
00225   return &packetInfo[registeredPacketCnt - 1];
00226   //    }
00227   // TODO: what if space for packets is exceeded??
00228   //    return NULL;
00229 }
00230 
00231 void parseRxFifo(void)
00232 {
00233   static uint8_t packetType;
00234   static uint8_t flag;
00235   static int packetSize = 0;
00236   static int rxCount = 0;
00237   static uint16_t checksum_computed = 0;
00238   static uint16_t checksum_received = 0;
00239   static uint32_t syncstate = 0;
00240   static HLI_ACK packet_ack;
00241   uint32_t i = 0;
00242   uint8_t rxdata = 0;
00243 
00244   if (rxFifo.inUse == 1)
00245     return;
00246 
00247   //    UART0_DISABLE_RX_INT;
00248 
00249   while (Fifo_readByte(&rxFifo, &rxdata))
00250   {
00251 
00252     if (syncstate == 0)
00253     {
00254       if (rxdata == 'a')
00255         syncstate++;
00256       else
00257         syncstate = 0;
00258 
00259       rxCount = 0;
00260       checksum_received = 0;
00261       packetSize = 0;
00262       flag = 0;
00263     }
00264     else if (syncstate == 1)
00265     {
00266       if (rxdata == '*')
00267         syncstate++;
00268       else
00269         syncstate = 0;
00270     }
00271     else if (syncstate == 2)
00272     {
00273       if (rxdata == '>')
00274         syncstate++;
00275       else
00276         syncstate = 0;
00277     }
00278     else if (syncstate == 3)
00279     {
00280       packetSize = rxdata; // get size of packet
00281       syncstate++;
00282     }
00283     else if (syncstate == 4)
00284     {
00285       packetType = rxdata; // get packet type
00286       if (packetSize < 1)
00287         syncstate = 0;
00288       else
00289       {
00290         rxCount = packetSize;
00291         syncstate++;
00292       }
00293     }
00294     else if (syncstate == 5)
00295     {
00296       flag = rxdata;
00297       syncstate++;
00298     }
00299     else if (syncstate == 6) // read data
00300     {
00301       rxParseBuffer[packetSize - rxCount] = rxdata;
00302       rxCount--;
00303 
00304       if (rxCount == 0)
00305       {
00306         syncstate++;
00307       }
00308     }
00309     else if (syncstate == 7) // first byte of checksum
00310     {
00311       checksum_received = rxdata & 0xff;
00312       syncstate++;
00313     }
00314     else if (syncstate == 8) // second byte of checksum + check (and dispatch?)
00315     {
00316       checksum_received |= ((unsigned short)rxdata << 8);
00317       UART_rxPacketCount++;
00318 
00319       checksum_computed = crc16(&packetType, 1, 0xff);
00320       checksum_computed = crc16(&flag, 1, checksum_computed);
00321       checksum_computed = crc16(rxParseBuffer, packetSize, checksum_computed);
00322 
00323       if (checksum_received == checksum_computed)
00324       {
00325         UART_rxGoodPacketCount++;
00326         for (i = 0; i < registeredPacketCnt; i++)
00327         {
00328           if (packetType == packetInfo[i].descriptor)
00329           {
00330             memcpy((packetInfo[i].data), rxParseBuffer, packetSize);
00331             packetInfo[i].updated = 1;
00332             if (flag & HLI_COMM_ACK)
00333             {
00334               packet_ack.ack_packet = flag;
00335               writePacket2Ringbuffer(HLI_PACKET_ID_ACK, &packet_ack, sizeof(packet_ack));
00336             }
00337             break;
00338           }
00339         }
00340       }
00341       syncstate = 0;
00342     }
00343     else
00344       syncstate = 0;
00345   }
00346   //    UART0_ENABLE_RX_INT;
00347 }
00348 
00349 int writePacket2Ringbuffer(uint8_t descriptor, void * data, uint8_t length)
00350 {
00351   static uint8_t header[] = {0xFF, 0x09, 0, 0};
00352   uint16_t checksum = 0;
00353   int state = 0;
00354 
00355   header[2] = length;
00356   header[3] = descriptor;
00357   checksum = crc16(&descriptor, 1, 0xff);
00358   checksum = crc16(data, length, checksum);
00359 
00360   state = 1;
00361   state &= UART0_writeFifo(header, sizeof(header));
00362   state &= UART0_writeFifo(data, length);
00363   state &= UART0_writeFifo(&checksum, sizeof(checksum));
00364 
00365   return state;
00366 }
00367 
00368 uint8_t UART0_writeFifo(void * data, uint32_t length)
00369 {
00370   uint8_t ret = 0;
00371   short freemem;
00372   //    while(txFifo.inUse);
00373   //    UART0_DISABLE_TX_INT;
00374   ret = Fifo_writeBlock(&txFifo, data, length);
00375   freemem = Fifo_availableMemory(&txFifo);
00376   if (freemem < uart0_min_tx_buffer)
00377     uart0_min_tx_buffer = freemem;
00378   //    UART0_ENABLE_TX_INT;
00379   return ret;
00380 }
00381 
00382 void UARTInitialize(unsigned int baud)
00383 {
00384   UART0_DISABLE_RX_INT;
00385   UART0_DISABLE_TX_INT;
00386 
00387   unsigned int divisor = peripheralClockFrequency() / (16 * baud);
00388 
00389   //UART0
00390   U0LCR = 0x83; /* 8 bit, 1 stop bit, no parity, enable DLAB */
00391   U0DLL = divisor & 0xFF;
00392   U0DLM = (divisor >> 8) & 0xFF;
00393   U0LCR &= ~0x80; /* Disable DLAB */
00394   U0FCR = UFCR_FIFO_ENABLE | UFCR_FIFO_TRIG8 | UFCR_RX_FIFO_RESET | UFCR_TX_FIFO_RESET;//1; fifo enable, trigger interrupt after 8 bytes in the fifo
00395   Fifo_initialize(&rxFifo, rxBuffer, UART0_RX_BUFFERSIZE);
00396   Fifo_initialize(&txFifo, txBuffer, UART0_TX_BUFFERSIZE);
00397 
00398   UART0_ENABLE_RX_INT;
00399   UART0_ENABLE_TX_INT;
00400 }
00401 
00402 void startAutoBaud(void)
00403 {
00404   if (U0ACR & 0x01)
00405     return;
00406 
00407   U0ACR = 0x01 | 0x04;// start, mode 0, autorestart
00408   U0IER |= ((1 << 8) | (1 << 9)); //enable ABEO and ABTO interrupts
00409 }
00410 
00411 void UART0_rxFlush(void)
00412 {
00413   U0FCR |= UFCR_RX_FIFO_RESET;
00414   Fifo_reset(&rxFifo);
00415 }
00416 void UART0_txFlush(void)
00417 {
00418   U0FCR |= UFCR_TX_FIFO_RESET;
00419 }
00420 
00421 int UART0_txEmpty(void)
00422 {
00423   return (U0LSR & (ULSR_THRE | ULSR_TEMT)) == (ULSR_THRE | ULSR_TEMT);
00424 }
00425 
00426 //Write to UART0
00427 void UARTWriteChar(unsigned char ch)
00428 {
00429   while ((U0LSR & 0x20) == 0)
00430     ;
00431   U0THR = ch;
00432 }
00433 
00434 unsigned char UARTReadChar(void)
00435 {
00436   while ((U0LSR & 0x01) == 0)
00437     ;
00438   return U0RBR;
00439 }
00440 
00441 void __putchar(int ch)
00442 {
00443   if (ch == '\n')
00444     UARTWriteChar('\r');
00445   UARTWriteChar(ch);
00446 }
00447 
00448 void UART_send(char *buffer, unsigned char length)
00449 {
00450   unsigned char cnt = 0;
00451   while (!(U0LSR & 0x20))
00452     ; //wait until U0THR and U0TSR are both empty
00453   while (length--)
00454   {
00455     U0THR = buffer[cnt++];
00456     if (cnt > 15)
00457     {
00458       while (!(U0LSR & 0x20))
00459         ; //wait until U0THR is empty
00460     }
00461   }
00462 }
00463 
00464 void UART_send_ringbuffer(void)
00465 {
00466   uint8_t t;
00467   if (!transmission_running)
00468   {
00469     if (Fifo_readByte(&txFifo, &t))
00470     {
00471       transmission_running = 1;
00472       UARTWriteChar(t);
00473     }
00474   }
00475 }
00476 
00477 inline uint16_t crc_update(uint16_t crc, uint8_t data)
00478 {
00479   data ^= (crc & 0xff);
00480   data ^= data << 4;
00481 
00482   return ((((uint16_t)data << 8) | ((crc >> 8) & 0xff)) ^ (uint8_t)(data >> 4) ^ ((uint16_t)data << 3));
00483 }
00484 
00485 inline uint16_t crc16(void* data, uint16_t cnt, uint16_t crc)
00486 {
00487   uint8_t * ptr = (uint8_t *)data;
00488   int i;
00489 
00490   for (i = 0; i < cnt; i++)
00491   {
00492     crc = crc_update(crc, *ptr);
00493     ptr++;
00494   }
00495   return crc;
00496 }
00497 


asctec_hl_firmware
Author(s): Markus Achtelik, Michael Achtelik, Stephan Weiss, Laurent Kneip
autogenerated on Tue Jan 7 2014 11:05:19