uart.c
Go to the documentation of this file.
00001 /*
00002 
00003 Copyright (c) 2011, Ascending Technologies GmbH
00004 All rights reserved.
00005 
00006 Redistribution and use in source and binary forms, with or without
00007 modification, are permitted provided that the following conditions are met:
00008 
00009  * Redistributions of source code must retain the above copyright notice,
00010    this list of conditions and the following disclaimer.
00011  * Redistributions in binary form must reproduce the above copyright
00012    notice, this list of conditions and the following disclaimer in the
00013    documentation and/or other materials provided with the distribution.
00014 
00015 THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND ANY
00016 EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00017 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00018 DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE FOR ANY
00019 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00020 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00021 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00022 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00023 LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
00024 OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
00025 DAMAGE.
00026 
00027  */
00028 
00029 #include "LPC214x.h"
00030 #include "system.h"
00031 #include "main.h"
00032 #include "uart.h"
00033 #include "irq.h"
00034 #include "hardware.h"
00035 #include "gpsmath.h"
00036 #include "ssp.h"
00037 #include "sdk.h"
00038 #include "ublox.h"
00039 
00040 unsigned char packets;
00041 unsigned char DataOutputsPerSecond;
00042 unsigned int uart_cnt;
00043 
00044 unsigned char data_requested=0;
00045 extern int ZeroDepth;
00046 
00047 unsigned short current_chksum;
00048 unsigned char chksum_to_check=0;
00049 unsigned char chksum_trigger=1;
00050 
00051 unsigned char transmission_running=0;
00052 unsigned char transmission1_running=0;
00053 unsigned char trigger_transmission=0;
00054 
00055 volatile unsigned char baudrate1_change=0;
00056 
00057 unsigned char send_buffer[16];
00058 unsigned char *tx_buff;
00059 unsigned char UART_syncstate=0;
00060 unsigned char UART1_syncstate=0;
00061 unsigned int UART_rxcount=0;
00062 unsigned char *UART_rxptr;
00063 unsigned int UART1_rxcount=0;
00064 unsigned char *UART1_rxptr;
00065 
00066 unsigned char UART_CalibDoneFlag = 0;
00067 
00068 static volatile unsigned char rb_busy=0;
00069 
00070 unsigned char startstring[]={'>','*','>'};
00071 unsigned char stopstring[]={'<','#','<'};
00072 
00073 
00074 void uart1ISR(void) __irq
00075 {
00076   unsigned char t;
00077   IENABLE;
00078   unsigned iir = U1IIR;
00079   // Handle UART interrupt
00080   switch ((iir >> 1) & 0x7)
00081     {
00082       case 1:
00083                   // THRE interrupt
00084                  if (ringbuffer1(RBREAD, &t, 1))
00085                  {
00086                    transmission1_running=1;
00087                    UART1WriteChar(t);
00088                  }
00089                  else
00090                  {
00091                    transmission1_running=0;
00092                  }
00093         break;
00094       case 2:
00095         // RX interrupt
00096             uBloxReceiveHandler(U1RBR);
00097             break;
00098       case 3:
00099         // RLS interrupt
00100         break;
00101       case 6:
00102         // CTI interrupt
00103         break;
00104    }
00105   IDISABLE;
00106   VICVectAddr = 0;              /* Acknowledge Interrupt */
00107 }
00108 
00109 
00110 
00111 void uart0ISR(void) __irq
00112 {
00113   unsigned char t;
00114   unsigned char UART_rxdata;
00115 
00116 
00117   // Read IIR to clear interrupt and find out the cause
00118   IENABLE;
00119   unsigned iir = U0IIR;
00120   // Handle UART interrupt
00121   switch ((iir >> 1) & 0x7)
00122     {
00123       case 1:
00124         // THRE interrupt
00125                 if(!(IOPIN0&(1<<CTS_RADIO)))
00126                 {
00127                         trigger_transmission=0;
00128                          if (ringbuffer(RBREAD, &t, 1))
00129                      {
00130                        transmission_running=1;
00131                        UARTWriteChar(t);
00132                      }
00133                      else
00134                      {
00135                        transmission_running=0;
00136                      }
00137                 }
00138                 else
00139                 {
00140                         trigger_transmission=1;
00141                 }
00142                 break;
00143 
00144       case 2:
00145         // RDA interrupt - put your HL_serial_0 receive state machine here!
00146         UART_rxdata = U0RBR;
00147 
00148         if (UART_syncstate==0)
00149                 {
00150                         if (UART_rxdata=='>') UART_syncstate++; else UART_syncstate=0;
00151                 }
00152                 else if (UART_syncstate==1)
00153                 {
00154                         if (UART_rxdata=='*') UART_syncstate++; else UART_syncstate=0;
00155                 }
00156                 else if (UART_syncstate==2)
00157                 {
00158                         if (UART_rxdata=='>') UART_syncstate++; else UART_syncstate=0;
00159                 }
00160                 else if (UART_syncstate==3)
00161                 {
00162                         //synchronized to start string => receive your data from here
00163            UART_syncstate=0;
00164         }
00165                 else UART_syncstate=0;
00166 
00167         break;
00168       case 3:
00169         // RLS interrupt
00170         break;
00171       case 6:
00172         // CTI interrupt
00173         break;
00174   }
00175   IDISABLE;
00176   VICVectAddr = 0;              // Acknowledge Interrupt
00177  }
00178 
00179 
00180 void UARTInitialize(unsigned int baud)
00181 {
00182   unsigned int divisor = peripheralClockFrequency() / (16 * baud);
00183 
00184   //UART0
00185   U0LCR = 0x83; /* 8 bit, 1 stop bit, no parity, enable DLAB */
00186   U0DLL = divisor & 0xFF;
00187   U0DLM = (divisor >> 8) & 0xFF;
00188   U0LCR &= ~0x80; /* Disable DLAB */
00189   U0FCR = 1;
00190 
00191 
00192 }
00193 
00194 void UART1Initialize(unsigned int baud)
00195 {
00196   unsigned int divisor = peripheralClockFrequency() / (16 * baud);
00197 //UART1
00198   U1LCR = 0x83; /* 8 bit, 1 stop bit, no parity, enable DLAB */
00199   U1DLL = divisor & 0xFF;
00200   U1DLM = (divisor >> 8) & 0xFF;
00201   U1LCR &= ~0x80; /* Disable DLAB */
00202   U1FCR = 1;
00203 }
00204 
00205 
00206 //Write to UART0
00207 void UARTWriteChar(unsigned char ch)
00208 {
00209   while ((U0LSR & 0x20) == 0);
00210   U0THR = ch;
00211 }
00212 //Write to UART1
00213 void UART1WriteChar(unsigned char ch)
00214 {
00215   while ((U1LSR & 0x20) == 0);
00216   U1THR = ch;
00217 }
00218 
00219 unsigned char UARTReadChar(void)
00220 {
00221   while ((U0LSR & 0x01) == 0);
00222   return U0RBR;
00223 }
00224 
00225 unsigned char UART1ReadChar(void)
00226 {
00227   while ((U1LSR & 0x01) == 0);
00228   return U1RBR;
00229 }
00230 
00231 void __putchar(int ch)
00232 {
00233   if (ch == '\n')
00234     UARTWriteChar('\r');
00235   UARTWriteChar(ch);
00236 }
00237 
00238 void UART_send(char *buffer, unsigned char length)
00239 {
00240   unsigned char cnt=0;
00241   while (!(U0LSR & 0x20)); //wait until U0THR and U0TSR are both empty
00242   while(length--)
00243   {
00244     U0THR = buffer[cnt++];
00245     if(cnt>15)
00246     {
00247       while (!(U0LSR & 0x20)); //wait until U0THR is empty
00248     }
00249   }
00250 }
00251 
00252 void UART1_send(unsigned char *buffer, unsigned char length)
00253 {
00254   unsigned char cnt=0;
00255   while(length--)
00256   {
00257     while (!(U1LSR & 0x20)); //wait until U1THR is empty
00258     U1THR = buffer[cnt++];
00259   }
00260 }
00261 
00262 
00263 void UART_send_ringbuffer(void)
00264 {
00265   unsigned char t;
00266   if(!transmission_running)
00267   {
00268     if(ringbuffer(RBREAD, &t, 1))
00269     {
00270       transmission_running=1;
00271       UARTWriteChar(t);
00272     }
00273   }
00274 }
00275 
00276 void UART1_send_ringbuffer(void)
00277 {
00278   unsigned char t;
00279   if(!transmission1_running)
00280   {
00281     if(ringbuffer1(RBREAD, &t, 1))
00282     {
00283       transmission1_running=1;
00284       UART1WriteChar(t);
00285     }
00286   }
00287 }
00288 
00289 void UART_SendPacket(void *data, unsigned short count, unsigned char packetdescriptor) //example to send data packets as on LL_serial_0
00290 {
00291   unsigned short crc;
00292   int state;
00293       state=ringbuffer(RBWRITE, startstring, 3);
00294       state=ringbuffer(RBWRITE, (unsigned char *) &count, 2);
00295       state=ringbuffer(RBWRITE, &packetdescriptor, 1);
00296       state=ringbuffer(RBWRITE, data, count);
00297                 crc=crc16(data,count);
00298       state=ringbuffer(RBWRITE, (unsigned char *) &crc, 2);
00299       state=ringbuffer(RBWRITE, stopstring, 3);
00300       UART_send_ringbuffer();
00301 }
00302 
00303 //example CRC16 function
00304 unsigned short crc_update (unsigned short crc, unsigned char data)
00305      {
00306          data ^= (crc & 0xff);
00307          data ^= data << 4;
00308 
00309          return ((((unsigned short )data << 8) | ((crc>>8)&0xff)) ^ (unsigned char )(data >> 4)
00310                  ^ ((unsigned short )data << 3));
00311      }
00312 
00313  unsigned short crc16(void* data, unsigned short cnt)
00314  {
00315    unsigned short crc=0xff;
00316    unsigned char * ptr=(unsigned char *) data;
00317    int i;
00318 
00319    for (i=0;i<cnt;i++)
00320      {
00321        crc=crc_update(crc,*ptr);
00322        ptr++;
00323      }
00324    return crc;
00325  }
00326 
00327 // no longer a ringbuffer! - now it's a FIFO
00328 int ringbuffer(unsigned char rw, unsigned char *data, unsigned int count)       //returns 1 when write/read was successful, 0 elsewise
00329 {
00330     static volatile unsigned char buffer[RINGBUFFERSIZE];
00331 //      static volatile unsigned int pfirst=0, plast=0; //Pointers to first and last to read byte
00332         static volatile unsigned int read_pointer, write_pointer;
00333         static volatile unsigned int content=0;
00334         unsigned int p=0;
00335     unsigned int p2=0;
00336 
00337         if(rw==RBWRITE)
00338         {
00339                 if(count<RINGBUFFERSIZE-content)        //enough space in buffer?
00340                 {
00341                         while(p<count)
00342                         {
00343                                 buffer[write_pointer++]=data[p++];
00344                         }
00345             content+=count;
00346             return(1);
00347                 }
00348         }
00349         else if(rw==RBREAD)
00350         {
00351                 if(content>=count)
00352                 {
00353                         while(p2<count)
00354                         {
00355                                 data[p2++]=buffer[read_pointer++];
00356                         }
00357             content-=count;
00358             if(!content) //buffer empty
00359             {
00360                 write_pointer=0;
00361                 read_pointer=0;
00362             }
00363                         return(1);
00364                 }
00365         }
00366         else if(rw==RBFREE)
00367         {
00368           if(content) return 0;
00369           else return(RINGBUFFERSIZE-11);
00370         }
00371 
00372         return(0);
00373 }
00374 
00375 int ringbuffer1(unsigned char rw, unsigned char *data, unsigned int count)      //returns 1 when write/read was successful, 0 elsewise
00376 {
00377     static volatile unsigned char buffer[RINGBUFFERSIZE];
00378 //      static volatile unsigned int pfirst=0, plast=0; //Pointers to first and last to read byte
00379         static volatile unsigned int read_pointer, write_pointer;
00380         static volatile unsigned int content=0;
00381         unsigned int p=0;
00382     unsigned int p2=0;
00383 
00384         if(rw==RBWRITE)
00385         {
00386                 if(count<RINGBUFFERSIZE-content)        //enough space in buffer?
00387                 {
00388                         while(p<count)
00389                         {
00390                                 buffer[write_pointer++]=data[p++];
00391                         }
00392             content+=count;
00393             return(1);
00394                 }
00395         }
00396         else if(rw==RBREAD)
00397         {
00398                 if(content>=count)
00399                 {
00400                         while(p2<count)
00401                         {
00402                                 data[p2++]=buffer[read_pointer++];
00403                         }
00404             content-=count;
00405             if(!content) //buffer empty
00406             {
00407                 write_pointer=0;
00408                 read_pointer=0;
00409             }
00410                         return(1);
00411                 }
00412         }
00413         else if(rw==RBFREE)
00414         {
00415           if(content) return 0;
00416           else return(RINGBUFFERSIZE-11);
00417         }
00418 
00419         return(0);
00420 }


asctec_hl_firmware
Author(s): Markus Achtelik, Michael Achtelik, Stephan Weiss, Laurent Kneip
autogenerated on Tue Dec 17 2013 11:39:27