uart.c
Go to the documentation of this file.
00001 #include <string.h>
00002 #include <mav_common/comm.h>
00003 
00004 #include "LPC214x.h"
00005 #include "interrupt_utils.h"
00006 #include "system.h"
00007 #include "main.h"
00008 #include "uart.h"
00009 #include "irq.h"
00010 #include "hardware.h"
00011 #include "gpsmath.h"
00012 #include "ssp.h"
00013 #include "lpcUART.h"
00014 
00015 volatile unsigned char transmission_running = 0;
00016 
00017 unsigned char UART_syncstate = 0;
00018 unsigned int UART_rxcount = 0;
00019 unsigned char *UART_rxptr;
00020 
00021 unsigned uart0_rx_cpsr;
00022 unsigned uart0_tx_cpsr;
00023 
00024 #define UART0_DISABLE_TX_INT uart0_tx_cpsr=disableIRQ();U0IER &= ~UIER_ETBEI;restoreIRQ(uart0_tx_cpsr);
00025 #define UART0_ENABLE_TX_INT  uart0_tx_cpsr=disableIRQ();U0IER |= UIER_ETBEI;restoreIRQ(uart0_tx_cpsr);
00026 #define UART0_DISABLE_RX_INT uart0_rx_cpsr=disableIRQ();U0IER &= ~UIER_ERBFI;restoreIRQ(uart0_rx_cpsr);
00027 #define UART0_ENABLE_RX_INT  uart0_rx_cpsr=disableIRQ();U0IER |= UIER_ERBFI;restoreIRQ(uart0_rx_cpsr);
00028 
00029 short uart0_min_tx_buffer = UART0_TX_BUFFERSIZE;
00030 short uart0_min_rx_buffer = UART0_RX_BUFFERSIZE;
00031 
00032 uint8_t rxBuffer[UART0_RX_BUFFERSIZE];
00033 uint8_t rxParseBuffer[UART0_RX_BUFFERSIZE];
00034 Fifo rxFifo;
00035 
00036 uint8_t txBuffer[UART0_TX_BUFFERSIZE];
00037 Fifo txFifo;
00038 
00039 volatile unsigned int UART_rxPacketCount = 0;
00040 volatile unsigned int UART_rxGoodPacketCount = 0;
00041 
00042 PacketInfo packetInfo[PACKET_INFO_SIZE];
00043 uint32_t registeredPacketCnt = 0;
00044 
00045 volatile char autobaud_in_progress = 0;
00046 
00047 void uart0ISR(void) __irq
00048 {
00049   uint8_t t;
00050   uint16_t iid;
00051   short freemem = 0;
00052 
00053   // Read IIR to clear interrupt and find out the cause
00054   while (((iid = U0IIR) & UIIR_NO_INT) == 0)
00055   {
00056     if (iid & 0x100)
00057     {
00058       autobaud_in_progress = 1;
00059       U0ACR |= 0x100; //clear ABEO interrupt
00060       U0ACR &= ~0x01; // disable autobaud
00061       U0IER &= ~((1 << 8) | (1 << 9)); //disable ABEO and ABTO interrupts
00062 
00063       autobaud_in_progress = 0;
00064     }
00065 
00066     if (iid & 0x200)
00067     {
00068       autobaud_in_progress = 1;
00069       U0ACR |= 0x200; //clear ABTO int
00070 
00071       autobaud_in_progress = 0;
00072     }
00073 
00074     switch (iid & UIIR_ID_MASK)
00075     {
00076       case UIIR_RLS_INT: // Receive Line Status
00077         U0LSR; // read LSR to clear
00078         break;
00079 
00080       case UIIR_CTI_INT: // <-- keep this together, in order to read remaining bytes below fifo threshold
00081       case UIIR_RDA_INT:
00082         // RDA interrupt
00083         //receive handler
00084         rxFifo.inUse = 1;
00085         do
00086         { // read from fifo as long as there is data available
00087           t = U0RBR;
00088           freemem = Fifo_availableMemory(&rxFifo);
00089           if (freemem < uart0_min_rx_buffer)
00090             uart0_min_rx_buffer = freemem;
00091           if (!Fifo_writeByte(&rxFifo, t))
00092             break;
00093         } while (U0LSR & ULSR_RDR);
00094         rxFifo.inUse = 0;
00095 
00096         break;
00097 
00098       case UIIR_THRE_INT:
00099         // THRE interrupt
00100         if(!(IOPIN0&(1<<CTS_RADIO))){
00101           txFifo.inUse = 1;
00102           while (U0LSR & ULSR_THRE)
00103           {
00104             if (Fifo_readByte(&txFifo, &t))
00105             {
00106               U0THR = t;
00107             }
00108             else
00109             {
00110               transmission_running = 0;
00111               break;
00112             }
00113           }
00114           txFifo.inUse = 0;
00115         }
00116         break;
00117 
00118       default: // Unknown
00119         U0LSR;
00120         U0RBR;
00121         break;
00122     }
00123   }
00124   VICVectAddr = 0; // Acknowledge Interrupt
00125 }
00126 
00127 void Fifo_initialize(Fifo * fifo, uint8_t * buffer, uint32_t bufferSize)
00128 {
00129   fifo->buffer = buffer;
00130   fifo->bufferSize = bufferSize;
00131   fifo->readIdx = 0;
00132   fifo->writeIdx = 0;
00133   fifo->tmp = 0;
00134   fifo->mask = bufferSize - 1;
00135   fifo->inUse = 0;
00136 }
00137 
00138 uint8_t Fifo_writeByte(Fifo * fifo, uint8_t byte)
00139 {
00140   fifo->tmp = ((fifo->writeIdx + 1) & fifo->mask);
00141   if (fifo->readIdx == fifo->tmp)
00142     return 0;
00143   fifo->buffer[fifo->writeIdx] = byte;
00144   fifo->writeIdx = fifo->tmp;
00145   return 1;
00146 }
00147 
00148 uint8_t Fifo_writeBlock(Fifo * fifo, void *data, uint32_t length)
00149 {
00150   if (Fifo_availableMemory(fifo) <= length)
00151     return 0;
00152   uint8_t *ptr = (uint8_t *)data;
00153   while (length--)
00154   {
00155     fifo->buffer[fifo->writeIdx] = *ptr++;
00156     fifo->writeIdx = (fifo->writeIdx + 1) & fifo->mask;
00157   }
00158 
00159   //    //safe method
00160   //    int i=0;
00161   //    uint8_t *ptr = (uint8_t *)data;
00162   //    for(i=0; i<length; i++){
00163   //            if(!Fifo_writeByte(fifo, ptr[i]))
00164   //                    return 0;
00165   //    }
00166 
00167   return 1;
00168 }
00169 
00170 uint8_t Fifo_readByte(Fifo * fifo, uint8_t * byte)
00171 {
00172   if (fifo->readIdx == fifo->writeIdx)
00173     return 0;
00174   *byte = fifo->buffer[fifo->readIdx];
00175   fifo->readIdx = (fifo->readIdx + 1) & fifo->mask;
00176   return 1;
00177 }
00178 
00179 uint16_t Fifo_availableMemory(Fifo * fifo)
00180 {
00181   return (fifo->readIdx - fifo->writeIdx - 1) & fifo->mask;
00182 }
00183 
00184 void Fifo_reset(Fifo * fifo)
00185 {
00186   fifo->writeIdx = 0;
00187   fifo->readIdx = 0;
00188 }
00189 
00190 PacketInfo* registerPacket(uint8_t descriptor, void * data)
00191 {
00192   //    if(registeredPacketCnt < PACKET_INFO_SIZE){
00193   packetInfo[registeredPacketCnt].data = data;
00194   packetInfo[registeredPacketCnt].descriptor = descriptor;
00195   packetInfo[registeredPacketCnt].updated = 0;
00196   registeredPacketCnt++;
00197   return &packetInfo[registeredPacketCnt - 1];
00198   //    }
00199   // TODO: what if space for packets is exceeded??
00200   //    return NULL;
00201 }
00202 
00203 void parseRxFifo(void)
00204 {
00205   static uint8_t packetType;
00206   static uint8_t flag;
00207   static int packetSize = 0;
00208   static int rxCount = 0;
00209   static uint16_t checksum_computed = 0;
00210   static uint16_t checksum_received = 0;
00211   static uint32_t syncstate = 0;
00212   static MAV_ACK_PKT packet_ack;
00213   uint32_t i = 0;
00214   uint8_t rxdata = 0;
00215 
00216   if (rxFifo.inUse == 1)
00217     return;
00218 
00219   //    UART0_DISABLE_RX_INT;
00220 
00221   while (Fifo_readByte(&rxFifo, &rxdata))
00222   {
00223 
00224     if (syncstate == 0)
00225     {
00226       if (rxdata == '>')
00227         syncstate++;
00228       else
00229         syncstate = 0;
00230 
00231       rxCount = 0;
00232       checksum_received = 0;
00233       UART_rxptr = rxParseBuffer;
00234       packetSize = 0;
00235       flag = 0;
00236     }
00237     else if (syncstate == 1)
00238     {
00239       if (rxdata == '*')
00240         syncstate++;
00241       else
00242         syncstate = 0;
00243     }
00244     else if (syncstate == 2)
00245     {
00246       if (rxdata == '>')
00247         syncstate++;
00248       else
00249         syncstate = 0;
00250     }
00251     else if (syncstate == 3)
00252     {
00253       packetSize = rxdata; // get size of packet
00254       syncstate++;
00255     }
00256     else if (syncstate == 4)
00257     {
00258       packetType = rxdata; // get packet type
00259       if (packetSize < 1)
00260         syncstate = 0;
00261       else
00262       {
00263         rxCount = packetSize;
00264         syncstate++;
00265       }
00266     }
00267     else if (syncstate == 5)
00268     {
00269       flag = rxdata;
00270       syncstate++;
00271     }
00272     else if (syncstate == 6) // read data
00273     {
00274       rxParseBuffer[packetSize - rxCount] = rxdata;
00275       rxCount--;
00276 
00277       if (rxCount == 0)
00278       {
00279         syncstate++;
00280       }
00281     }
00282     else if (syncstate == 7) // first byte of checksum
00283     {
00284       checksum_received = rxdata & 0xff;
00285       syncstate++;
00286     }
00287     else if (syncstate == 8) // second byte of checksum + check (and dispatch?)
00288     {
00289       checksum_received |= ((unsigned short)rxdata << 8);
00290       UART_rxPacketCount++;
00291 
00292       checksum_computed = crc16(&packetType, 1, 0xff);
00293       checksum_computed = crc16(&flag, 1, checksum_computed);
00294       checksum_computed = crc16(rxParseBuffer, packetSize, checksum_computed);
00295 
00296       if (checksum_received == checksum_computed)
00297       {
00298         UART_rxGoodPacketCount++;
00299         for (i = 0; i < registeredPacketCnt; i++)
00300         {
00301           if (packetType == packetInfo[i].descriptor)
00302           {
00303             memcpy((packetInfo[i].data), rxParseBuffer, packetSize);
00304             packetInfo[i].updated = 1;
00305             if (flag & MAV_COMM_ACK)
00306             {
00307               packet_ack.ack_packet = flag;
00308               writePacket2Ringbuffer(MAV_ACK_PKT_ID, &packet_ack, sizeof(packet_ack));
00309             }
00310             break;
00311           }
00312         }
00313       }
00314       syncstate = 0;
00315     }
00316     else
00317       syncstate = 0;
00318   }
00319   //    UART0_ENABLE_RX_INT;
00320 }
00321 
00322 inline int writePacket2Ringbuffer(uint8_t descriptor, void * data, uint8_t length)
00323 {
00324   static uint8_t header[] = {0xFF, 0x09, 0, 0};
00325   uint16_t checksum = 0;
00326   int state = 0;
00327 
00328   header[2] = length;
00329   header[3] = descriptor;
00330   checksum = crc16(&descriptor, 1, 0xff);
00331   checksum = crc16(data, length, checksum);
00332 
00333   state = 1;
00334   state &= UART0_writeFifo(header, sizeof(header));
00335   state &= UART0_writeFifo(data, length);
00336   state &= UART0_writeFifo(&checksum, sizeof(checksum));
00337 
00338   return state;
00339 }
00340 
00341 uint8_t UART0_writeFifo(void * data, uint32_t length)
00342 {
00343   uint8_t ret = 0;
00344   short freemem;
00345   //    while(txFifo.inUse);
00346   //    UART0_DISABLE_TX_INT;
00347   ret = Fifo_writeBlock(&txFifo, data, length);
00348   freemem = Fifo_availableMemory(&txFifo);
00349   if (freemem < uart0_min_tx_buffer)
00350     uart0_min_tx_buffer = freemem;
00351   //    UART0_ENABLE_TX_INT;
00352   return ret;
00353 }
00354 
00355 void UARTInitialize(unsigned int baud)
00356 {
00357   UART0_DISABLE_RX_INT;
00358   UART0_DISABLE_TX_INT;
00359 
00360   unsigned int divisor = peripheralClockFrequency() / (16 * baud);
00361 
00362   //UART0
00363   U0LCR = 0x83; /* 8 bit, 1 stop bit, no parity, enable DLAB */
00364   U0DLL = divisor & 0xFF;
00365   U0DLM = (divisor >> 8) & 0xFF;
00366   U0LCR &= ~0x80; /* Disable DLAB */
00367   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
00368   Fifo_initialize(&rxFifo, rxBuffer, UART0_RX_BUFFERSIZE);
00369   Fifo_initialize(&txFifo, txBuffer, UART0_TX_BUFFERSIZE);
00370 
00371   UART0_ENABLE_RX_INT;
00372   UART0_ENABLE_TX_INT;
00373 }
00374 
00375 void startAutoBaud(void)
00376 {
00377   if (U0ACR & 0x01)
00378     return;
00379 
00380   U0ACR = 0x01 | 0x04;// start, mode 0, autorestart
00381   U0IER |= ((1 << 8) | (1 << 9)); //enable ABEO and ABTO interrupts
00382 }
00383 
00384 void UART0_rxFlush(void)
00385 {
00386   U0FCR |= UFCR_RX_FIFO_RESET;
00387   Fifo_reset(&rxFifo);
00388 }
00389 void UART0_txFlush(void)
00390 {
00391   U0FCR |= UFCR_TX_FIFO_RESET;
00392 }
00393 
00394 int UART0_txEmpty(void)
00395 {
00396   return (U0LSR & (ULSR_THRE | ULSR_TEMT)) == (ULSR_THRE | ULSR_TEMT);
00397 }
00398 
00399 //Write to UART0
00400 void UARTWriteChar(unsigned char ch)
00401 {
00402   while ((U0LSR & 0x20) == 0)
00403     ;
00404   U0THR = ch;
00405 }
00406 
00407 unsigned char UARTReadChar(void)
00408 {
00409   while ((U0LSR & 0x01) == 0)
00410     ;
00411   return U0RBR;
00412 }
00413 
00414 void __putchar(int ch)
00415 {
00416   if (ch == '\n')
00417     UARTWriteChar('\r');
00418   UARTWriteChar(ch);
00419 }
00420 
00421 void UART_send(char *buffer, unsigned char length)
00422 {
00423   unsigned char cnt = 0;
00424   while (!(U0LSR & 0x20))
00425     ; //wait until U0THR and U0TSR are both empty
00426   while (length--)
00427   {
00428     U0THR = buffer[cnt++];
00429     if (cnt > 15)
00430     {
00431       while (!(U0LSR & 0x20))
00432         ; //wait until U0THR is empty
00433     }
00434   }
00435 }
00436 
00437 void UART_send_ringbuffer(void)
00438 {
00439   uint8_t t;
00440   if (!transmission_running)
00441   {
00442     if (Fifo_readByte(&txFifo, &t))
00443     {
00444       transmission_running = 1;
00445       UARTWriteChar(t);
00446     }
00447   }
00448 }
00449 
00450 uint16_t crc_update(uint16_t crc, uint8_t data)
00451 {
00452   data ^= (crc & 0xff);
00453   data ^= data << 4;
00454 
00455   return ((((uint16_t)data << 8) | ((crc >> 8) & 0xff)) ^ (uint8_t)(data >> 4) ^ ((uint16_t)data << 3));
00456 }
00457 
00458 uint16_t crc16(void* data, uint16_t cnt, uint16_t crc)
00459 {
00460   uint8_t * ptr = (uint8_t *)data;
00461   int i;
00462 
00463   for (i = 0; i < cnt; i++)
00464   {
00465     crc = crc_update(crc, *ptr);
00466     ptr++;
00467   }
00468   return crc;
00469 }
00470 


ccny_asctec_firmware_2
Author(s): Ivan Dryanovski, Roberto G. Valenti
autogenerated on Tue Jan 7 2014 11:04:17