usart.c
Go to the documentation of this file.
00001 /***************************************************************************
00002 ***  Fraunhofer IPA 
00003 ***  Robotersysteme 
00004 ***  Projekt: 3D cartography demonstrator
00005 ****************************************************************************
00006 ****************************************************************************
00007 ***  Autor: Julio Sagardoy (goa-js)
00008 ***************************************************************************/
00009 
00017 
00018 #include <avr/io.h>
00019 #include <avr/interrupt.h>
00020 #include <util/delay.h>
00021 
00023 #include "utils.h"
00024 #include "usart.h"
00025 
00026 #define UART_RX_BUFFER_SIZE 64     /* 2,4,8,16,32,64,128 or 256 bytes */
00027 #define UART_TX_BUFFER_SIZE 64
00028 
00029 #define UART_RX_BUFFER_MASK ( UART_RX_BUFFER_SIZE - 1 )
00030 #if ( UART_RX_BUFFER_SIZE & UART_RX_BUFFER_MASK )
00031         #error RX buffer size is not a power of 2
00032 #endif
00033 
00034 #define UART_TX_BUFFER_MASK ( UART_TX_BUFFER_SIZE - 1 )
00035 #if ( UART_TX_BUFFER_SIZE & UART_TX_BUFFER_MASK )
00036         #error TX buffer size is not a power of 2
00037 #endif
00038 
00039 static unsigned char UART_RxBuf[UART_RX_BUFFER_SIZE];
00040 static volatile char UART_RxHead;
00041 static volatile char UART_RxTail;
00042 static unsigned char UART_TxBuf[UART_TX_BUFFER_SIZE];
00043 static volatile char UART_TxHead;
00044 static volatile char UART_TxTail;
00045 
00048 unsigned char uart_getc( void )
00049 {
00050         unsigned char tmptail;
00051         
00052         while ( UART_RxHead == UART_RxTail )  /* Wait for incomming data  */
00053                 ;
00054         tmptail = ( UART_RxTail + 1 ) & UART_RX_BUFFER_MASK;/* Calculate buffer index */
00055 
00056         UART_RxTail = tmptail;                          /* Store new index */
00057 
00058         return UART_RxBuf[tmptail];                     /* Return data */
00059 }
00060 
00063 void uart_putc( unsigned char data )
00064 {
00065         unsigned char tmphead;
00066 
00067         tmphead = ( UART_TxHead + 1 ) & UART_TX_BUFFER_MASK;  /* Calculate buffer index */
00068         while ( tmphead == UART_TxTail )         /* Wait for free space in buffer */
00069                 ;
00070 
00071         UART_TxBuf[tmphead] = data;           /* Store data in buffer */
00072         UART_TxHead = tmphead;                /* Store new index */
00073 
00074         //UCR0 |= (1<<UDRIE);                    /* Enable UDRE interrupt */
00075         UCSR0B |= (1<<UDRIE0);          /* Enable UDRE interrupt */
00076 
00077 }
00078 
00081 char uart_gets( char* str )
00082 {
00083         char count = 0;
00084         char c;
00085         
00086         while(1)
00087         {
00088                 c = uart_getc();
00089                 if(c == '\n')
00090                 {
00091                         *str = '\0';    // null terminate string
00092                         return count;   // return read byte count
00093                 }
00094                 *str = c;
00095                 str++;
00096         }
00097 }
00098 
00101 void uart_puts( const char* str )
00102 {
00103         while( *str != '\0' )
00104                 uart_putc(*str++);      
00105                 
00106         uart_putc('\n');        //EOL
00107 }
00108 
00111 unsigned char uart_DataInReceiveBuffer()
00112 {
00113         return ( UART_RxHead != UART_RxTail ); /* Return 0 (FALSE) if the receive buffer is empty */
00114 }
00115 
00118 void uart_loopback( )
00119 {
00120         char c;
00121         do      
00122         {
00123                 c = uart_getc();
00124                 uart_putc( c );
00125         }
00126         while( c != 'q' );
00127 }
00128 
00129 void uart_bufferFlush( const int8_t b )
00130 {
00131         int8_t x=0;
00132         if( b == 0 )    // fush output buff
00133         {
00134                 UART_TxTail = x;
00135                 UART_TxHead = x;
00136         }
00137         else if (b == 1)        // flush input buff
00138         {
00139                 UART_RxTail = x;
00140                 UART_RxHead = x;
00141         }
00142         else            // flush both buffers
00143         {
00144                 UART_RxTail = x;
00145                 UART_RxHead = x;
00146                 UART_TxTail = x;
00147                 UART_TxHead = x;
00148         }
00149 }
00150 
00151 ISR(USART0_RX_vect)
00152 {
00153         unsigned char data;
00154         unsigned char tmphead;
00155 
00156         if( BITREAD(UCSR0A,UPE0) )      //Check for parity error
00157         {
00158                 UDR0;           //Discard character
00159                 #if( UART_ERROR_REPORT_ENABLED )
00160                 uart_putc(0x15);                //Send a NACK to the host       
00161                 #endif
00162         }
00163         else
00164         {
00165                 data = UDR0;                 /* Read the received data */
00166                 /* Calculate buffer index */
00167                 tmphead = ( UART_RxHead + 1 ) & UART_RX_BUFFER_MASK;
00168                 UART_RxHead = tmphead;      /* Store new index */
00169 
00170                 if ( tmphead == UART_RxTail )
00171                 {
00172                         /* ERROR! Receive buffer overflow */
00173                         //uart_flush();
00174                 }
00175                 UART_RxBuf[tmphead] = data; /* Store received data in buffer */
00176         }
00177 }
00178 
00179 ISR(USART0_UDRE_vect)
00180 {
00181         unsigned char tmptail;
00182 
00183         /* Check if all data is transmitted */
00184         if ( UART_TxHead != UART_TxTail )
00185         {
00186                 /* Calculate buffer index */
00187                 tmptail = ( UART_TxTail + 1 ) & UART_TX_BUFFER_MASK;
00188                 UART_TxTail = tmptail;      /* Store new index */
00189 
00190                 UDR0 = UART_TxBuf[tmptail];  /* Start transmition */
00191         }
00192         else
00193         {
00194                 UCSR0B &= ~(1<<UDRIE0);     /* Disable UDRE interrupt */
00195         }
00196 }
00197 
00200 void uart_init( )
00201 {
00202         int8_t x;
00203         
00204         UBRR0 = BAUD;
00205         /* Enable UART receiver and transmitter, receive interrupt */
00206         UCSR0B = ( (1<<RXCIE0) | (1<<RXEN0) | (1<<TXEN0) );
00207         UCSR0C = 0x26;; //Set parity even
00208         
00209     /* Flush receive buffer */
00210         x=0;
00211         
00212         UART_RxTail = x;
00213         UART_RxHead = x;
00214         UART_TxTail = x;
00215         UART_TxHead = x;
00216 }
00217 


cob_3d_mapping_demonstrator
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:46