summaryrefslogtreecommitdiffstats
path: root/source/AVR_Studio/Soccer/hal
diff options
context:
space:
mode:
Diffstat (limited to 'source/AVR_Studio/Soccer/hal')
-rwxr-xr-xsource/AVR_Studio/Soccer/hal/board.c210
-rwxr-xr-xsource/AVR_Studio/Soccer/hal/board.h38
-rwxr-xr-xsource/AVR_Studio/Soccer/hal/i2c.c217
-rwxr-xr-xsource/AVR_Studio/Soccer/hal/i2c.h69
-rwxr-xr-xsource/AVR_Studio/Soccer/hal/keylcd.c28
-rwxr-xr-xsource/AVR_Studio/Soccer/hal/keylcd.h25
-rwxr-xr-xsource/AVR_Studio/Soccer/hal/uart.c585
-rwxr-xr-xsource/AVR_Studio/Soccer/hal/uart.h179
8 files changed, 1351 insertions, 0 deletions
diff --git a/source/AVR_Studio/Soccer/hal/board.c b/source/AVR_Studio/Soccer/hal/board.c
new file mode 100755
index 0000000..d60834b
--- /dev/null
+++ b/source/AVR_Studio/Soccer/hal/board.c
@@ -0,0 +1,210 @@
+#include "board.h"
+
+static int beepFreq = 0;
+
+Board::Board() {
+ // Pin 1-6 sind ausgänge, 0 und 7 eingänge
+ DDRA = (1 << PA1) | (1 << PA2) | (1 << PA3) | (1 << PA4) | (1 << PA5) | (1 << PA6);
+ PORTA = 0; // Alle Low, kein Pollup
+
+ // Alle Ausgänge
+ DDRB = (1 << PB0) | (1 << PB1) | (1 << PB2) | (1 << PB3) | (1 << PB4) | (1 << PB5) | (1 << PB6) | (1 << PB7);
+ PORTB = (1 << PB1); // Alle Low bis PB1 , kein Pollup
+
+ // Alle Ausgänge
+ DDRC = (1 << PC0) | (1 << PC1) | (1 << PC2) | (1 << PC3) | (1 << PC4) | (1 << PC5) | (1 << PC6) | (1 << PC7);
+ PORTC = 0; // Alle Low, kein Pollup
+
+ // Alle Ausgänge bis auf PD0+1(I2C) + 2+3(RS232)
+ DDRD = (1 << PD2) | (1 << PD3) | (1 << PD4) | (1 << PD5) | (1 << PD6) | (1 << PD7);
+ PORTD = (1 << PD0) | (1 << PD1); // Pollup-Widerstand an PD0+1 aktivieren
+
+ // PE5 ist eingang
+ DDRE = (1 << PE0) | (1 << PE1) | (1 << PE2) | (1 << PE3) | (1 << PE4) | (1 << PE6) | (1 << PE7);
+ PORTE = 0; // Alle Low, kein Pollup
+
+ // Alle Eingänge mit Pollup
+ DDRF = 0;
+ PORTF = (1 << PF0) | (1 << PF1) | (1 << PF2) | (1 << PF3) | (1 << PF4) | (1 << PF5) | (1 << PF6) | (1 << PF7);
+
+ // Alle Ausgänge, PG0 und PG1 high
+ DDRG = (1 << PG0) | (1 << PG1) | (1 << PG2) | (1 << PG3) | (1 << PG4);
+ PORTG = (1 << PG0) | (1 << PG1);
+
+ // aktiviere Kanal A+C auf PWM1 mit 8Bit
+ //TCCR1A = (1<< COM1A1) | (1<< COM1C1) | (1<< WGM10);
+ //TCCR1B = (1<<ICNC1) | (1<<CS12) | (1<<CS10); // set clock/prescaler 1/1024 -> enable counter
+
+ // aktiviere Kanal A+B auf PWM3 mit 8Bit
+ //TCCR3A = (1<< COM3A1) | (1<< COM3B1) | (1<< WGM10);
+ //TCCR3B = (1<<ICNC3) | (1<<CS32) | (1<<CS30); // set clock/prescaler 1/1024 -> enable counter
+
+ // Schalte Motoren auf 0
+ motor(0,0);
+ motor(1,0);
+ motor(2,0);
+ motor(3,0);
+
+ // Uart-Interface einschalten
+ uart1_init( 10); // 9600 BAUD bei 16MHz Atmel
+
+ // aktiviere interrupt
+ sei();
+}
+
+Board::~Board() {
+
+}
+
+// Gibt einen Analogen Wert zurück
+int Board::GetADC(uint8_t channel) {
+ uint8_t i;
+ uint16_t result = 0;
+
+ // Den ADC aktivieren und Teilungsfaktor auf 64 stellen
+ ADCSRA = (1<<ADEN) | (1<<ADPS2) | (1<<ADPS1);
+
+ // Kanal des Multiplexers waehlen
+ ADMUX = channel;
+ // Interne Referenzspannung verwenden (also 2,56 V)
+ ADMUX |= (1<<REFS1) | (1<<REFS0);
+
+ // Den ADC initialisieren und einen sog. Dummyreadout machen
+ ADCSRA |= (1<<ADSC);
+ while(ADCSRA & (1<<ADSC));
+
+ // Jetzt 3x die analoge Spannung and Kanal channel auslesen
+ // und dann Durchschnittswert ausrechnen.
+ for(i=0; i<3; i++) {
+ // Eine Wandlung
+ ADCSRA |= (1<<ADSC);
+ // Auf Ergebnis warten...
+ while(ADCSRA & (1<<ADSC));
+
+ result += ADCW;
+ }
+
+ // ADC wieder deaktivieren
+ ADCSRA &= ~(1<<ADEN);
+
+ result /= 3;
+
+ return result;
+}
+
+void Board::beep(int freq) {
+ beepFreq = freq;
+}
+
+void Board::ledOff() {
+ PORTB |= (1 << PB1); // set bit
+}
+
+void Board::ledOn() {
+ PORTB &= ~(1 << PB1); // clear bit
+}
+
+void Board::led(bool status) {
+ if(status) ledOn();
+ else ledOff();
+}
+
+
+void Board::motor(int i, int speed)
+{
+ if((i < 0) || (i > 3)) return;
+ const int OFFSET = 40; // Motor does not work with very low ratio
+ const int PWM_MAX = 255;
+
+ int pwm = abs(speed)+OFFSET;
+ if(pwm > PWM_MAX) pwm = PWM_MAX;
+
+ if(i == 0)
+ {
+ MOTOR0_PWM = pwm;
+ if(speed > 0)
+ {
+ PORTD |= (1 << 5);//In 1 ein
+ PORTD &= ~(1 << 4);//In 2 aus
+ }
+ else if(speed < 0)
+ {
+ PORTD |= (1 << 4);//In 2 ein
+ PORTD &= ~(1 << 5);//In 1 aus
+ }
+ else
+ {
+ PORTD |= (1 << 4);//In 2 ein
+ PORTD |= (1 << 5);//In 1 ein
+ }
+ }
+ else if(i == 1)
+ {
+ MOTOR1_PWM = pwm;
+ if(speed > 0)
+ {
+ PORTD |= (1 << 6);//In 1 ein
+ PORTD &= ~(1 << 7);//In 2 aus
+ }
+ else if(speed < 0)
+ {
+ PORTD |= (1 << 7);//In 2 ein
+ PORTD &= ~(1 << 6);//In 1 aus
+ }
+ else
+ {
+ PORTD |= (1 << 6);//In 2 ein
+ PORTD |= (1 << 7);//In 1 ein
+ }
+ }
+ else if(i == 2)
+ {
+ MOTOR2_PWM = pwm;
+ if(speed > 0)
+ {
+ PORTB |= (1 << 0);//In 1 ein
+ PORTB &= ~(1 << 1);//In 2 aus
+ }
+ else if(speed < 0)
+ {
+ PORTB |= (1 << 1);//In 2 ein
+ PORTB &= ~(1 << 0);//In 1 aus
+ }
+ else
+ {
+ PORTB |= (1 << 1);//In 2 ein
+ PORTB |= (1 << 0);//In 1 ein
+ }
+ }
+ else if(i == 3)
+ {
+ DRIBBLER_PWM = pwm;
+ if(speed > 0)
+ {
+ PORTB |= (1 << 2);//In 1 ein
+ PORTB &= ~(1 << 3);//In 2 aus
+ }
+ else if(speed < 0)
+ {
+ PORTB |= (1 << 3);//In 2 ein
+ PORTB &= ~(1 << 2);//In 1 aus
+ }
+ else
+ {
+ PORTB |= (1 << 2);//In 2 ein
+ PORTB |= (1 << 3);//In 1 ein
+ }
+ }
+}
+
+//PWM routine für den Beeper
+ISR (TIMER0_OVF_vect)
+{
+ static int counter = 255;
+
+ if(counter > beepFreq/2) PORTG |= (1<<BEEPER_PIN);
+ else PORTG &= ~(1<<BEEPER_PIN);
+
+ if (counter==0) counter = 255;
+ else counter--;
+}
diff --git a/source/AVR_Studio/Soccer/hal/board.h b/source/AVR_Studio/Soccer/hal/board.h
new file mode 100755
index 0000000..dd177f1
--- /dev/null
+++ b/source/AVR_Studio/Soccer/hal/board.h
@@ -0,0 +1,38 @@
+#ifndef _BOARD_H_
+#define _BOARD_H_
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+#include <stdlib.h>
+#include "uart.h"
+
+//#define abs(a) ((a < 0)? -a : a)
+
+#define BEEPER_PIN PG2
+
+// Definiere PWM-Ports für die Motoren/Dribbler
+#define MOTOR0_PWM OCR3A
+#define MOTOR1_PWM OCR3B
+#define MOTOR2_PWM OCR1A
+#define DRIBBLER_PWM OCR1C
+
+#define UART_BAUD_RATE 9600
+
+class Board
+{
+private:
+public:
+ Board();
+ ~Board();
+
+ int GetADC(uint8_t channel);
+ void beep(int freq);
+ void ledOn();
+ void ledOff();
+ void led(bool status);
+ void motor(int i, int speed);
+};
+
+#endif
+
+
diff --git a/source/AVR_Studio/Soccer/hal/i2c.c b/source/AVR_Studio/Soccer/hal/i2c.c
new file mode 100755
index 0000000..65bf66b
--- /dev/null
+++ b/source/AVR_Studio/Soccer/hal/i2c.c
@@ -0,0 +1,217 @@
+#include "i2c.h"
+
+I2C::I2C()
+{
+ TWBR = 64; // I2C bitrate (must be 10 or higher)
+ TWCR = 4+64; // TWI enable bit + ackn
+ TWSR = 0; // prescaler
+
+ // I2C pull-ups are set in the board file //
+
+ err=0;
+}
+
+uint8_t I2C::error()
+{
+ return err;
+}
+
+
+void I2C::setSlaveAdress(uint8_t address)
+{
+ TWAR = address<<1; // slave address (shift by one since bit 0 has different meaning)
+}
+
+
+bool I2C::isAction()
+{
+ if (TWCR&(1<<TWINT)) return true;
+ else return false;
+}
+
+
+inline
+bool I2C::isActionGet()
+{
+ return ((TWSR&248)==TW_ST_SLA_ACK); // own I2C address received, read mode, ACK sent
+}
+
+
+inline
+bool I2C::isActionSend()
+{
+ return ((TWSR&248)==TW_SR_SLA_ACK); // own I2C address received, write mode, ACK sent
+}
+
+
+void I2C::sendStartSLA_W(uint8_t address)
+{
+ bool OK = false;
+ int counter = 0;
+
+ do {
+
+ TWCR |= BV(TWINT)|BV(TWSTA); // send start condition
+ while(!(TWCR&BV(TWINT))); // wait for OK
+
+ if ((TWSR&248)!=TW_START) { // start condition was sent -> OK
+ err=ERROR_NO_START;
+ return;
+ }
+
+ TWDR=(address<<1); // slave address + write mode
+ TWCR = BV(TWINT) | BV(TWEN) | BV(TWEA); // generate command
+
+ while(!(TWCR&128)) {}; // wait for OK
+ if ((TWSR&248)==TW_MT_SLA_ACK) OK=true; // SLA+W was sent, ACK received -> OK
+ if ((TWSR&248)==TW_MT_SLA_NACK) { // SLA+W was sent, ACK not received -> ERROR
+ counter++;
+
+ if (counter == 10) { // After 10 tries...
+ err=ERROR_NO_ACK; // ... return with ERROR_NO_ACK
+ return;
+ }
+ }
+
+ } while(!OK);
+
+ err=0; // OK
+}
+
+
+void I2C::sendStartSLA_R(uint8_t address)
+{
+ bool OK=false;
+ while (!OK) {
+ TWCR |= BV(TWINT)|BV(TWSTA); // send start condition
+// sbi(TWCR, TWSTA); // generate start condition
+ while(!(TWCR&128)); // wait for OK
+ if ((TWSR&248)==8); // start condition was sent -> OK
+
+ TWDR=(address<<1) | 1; // slave address + read mode
+ TWCR = BV(TWINT) | BV(TWEN) | BV(TWEA); // generate command
+
+ while(!(TWCR&128)); // wait for send OK + ACK/NACK from slave
+ if ((TWSR&248)==0x38); // Arbitration lost or NOT ACK -> ERROR
+ if ((TWSR&248)==0x40) OK=true; // SLA+R was sent, ACK received -> OK
+ if ((TWSR&248)==0x48); // SLA+W was sent, ACK not received -> ERROR
+ sbi(TWCR, TWINT); // OK
+ }
+}
+
+// This is used by send() called by the master //
+void I2C::sendByte(uint8_t data)
+{
+ TWDR = data; // send one data byte
+ TWCR = (1<<TWINT)|(1<<TWEA)|(1<<TWEN); // start transmission
+
+ while(!(TWCR&(1<<TWINT))); // wait for TWCR to become 0
+ if ((TWSR&248)==TW_MT_DATA_ACK); // data sent, ACK received -> OK
+ if ((TWSR&248)==TW_MT_DATA_NACK); // data sent, ACK not received -> ERROR
+}
+
+
+void I2C::sendStop()
+{
+ TWCR = BV(TWINT) | BV(TWEN) | BV(TWEA) | BV(TWSTO); // generate stop command
+}
+
+// Note: in qfix, the I2C address is the board identifier
+// and the first data byte ist the logical ID
+inline
+void I2C::send(uint8_t address, uint8_t data)
+{
+ send(address, &data, 1);
+}
+
+
+// Note: in qfix, the I2C address is the board identifier
+// and the first data byte ist the logical ID
+void I2C::send(uint8_t address, uint8_t* data, int length)
+{
+ sendStartSLA_W(address);
+ if (err!=0)
+ {
+ sendStop();
+ //err = ERROR_NOT_SENT;
+ return;
+ }
+
+ for (int i=0; i<length; i++) {
+ sendByte(data[i]);
+ }
+ sendStop();
+ err = 0; // OK
+}
+
+
+
+int I2C::receive(uint8_t* data)
+{
+ TWCR = (1<<TWINT)|(1<<TWEA)|(1<<TWEN);
+
+ while(!(TWCR&(1<<TWINT))); // wait for something
+
+ int len = 0;
+ while ((TWSR&248)==TW_SR_DATA_ACK) { // data received (in TWDR), ACK sent
+ data[len] = TWDR; // read received byte
+ len++;
+ TWCR = (1<<TWINT)|(1<<TWEA)|(1<<TWEN);
+ while(!(TWCR&(1<<TWINT))) { } // wait for OK
+ }
+
+ if ((TWSR&248)==TW_SR_STOP) { } // STOP (or new START) received -> OK
+ TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWEA); // generate command
+
+ return len;
+}
+
+
+void I2C::readByte(uint8_t& data)
+{
+ while(!isAction());
+
+ if ((TWSR&248)==0x50); // data received: NACK
+ if ((TWSR&248)==0x58); // data received: ACK
+ data = TWDR;
+ TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWEA); // generate command
+}
+
+
+void I2C::get(uint8_t address, uint8_t* data, int length)
+{
+ sendStartSLA_R(address);
+ if (err!=0)
+ {
+ sendStop();
+ err = ERROR_NOT_SENT;
+ return;
+ }
+
+ for (int i=0; i<length; i++) {
+ readByte(data[i]);
+ }
+ sendStop();
+}
+
+
+
+
+void I2C::returnBytes(uint8_t* data, int len, bool lastOne)
+{
+ for (int i=0; i<len; i++) {
+ TWDR=data[i]; // byte to send
+
+ if (i==len-1) TWCR = (1<<TWINT) | (1<<TWEN); // command for last byte (no TWEA is correct!)
+ else TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWEA); // command for all others
+
+ while(!(TWCR&(1<<TWINT))); // wait for OK
+
+ if ((TWSR&248)==0xB8); // data sent, ACK ACK received -> OK
+ if ((TWSR&248)==0xC0); // data sent, ACK not received -> ERROR
+ }
+ TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWEA); // generate command
+}
+
+
+
diff --git a/source/AVR_Studio/Soccer/hal/i2c.h b/source/AVR_Studio/Soccer/hal/i2c.h
new file mode 100755
index 0000000..e983bf2
--- /dev/null
+++ b/source/AVR_Studio/Soccer/hal/i2c.h
@@ -0,0 +1,69 @@
+#ifndef _IC2_H_
+#define _I2C_H_
+
+//------------------------------------------------------------------
+// qfixI2C.h
+//
+// This class is used for low-level I2C communication.
+//
+// For TW_ constants see compat/twi.h
+//
+// Copyright 2005-2006 by KTB mechatronics GmbH
+// Author: Stefan Enderle, Florian Schrapp
+//------------------------------------------------------------------
+
+
+
+#include "../global.h"
+#include <compat/twi.h>
+
+const int ACTION_SEND = 1;
+const int ACTION_GET = 2;
+const int ACTION_UNKNOWN = 3;
+
+
+const uint8_t ERROR_NO_ACK = 1;
+const uint8_t ERROR_NO_START = 2;
+const uint8_t ERROR_NOT_SENT = 3; // send() could not send byte(s)
+
+
+
+class I2C
+{
+private:
+ uint8_t err;
+ uint8_t adr;
+
+ void sendStartSLA_W(uint8_t address);
+ void sendStartSLA_R(uint8_t address);
+ void sendByte(uint8_t data);
+ void sendStop();
+ void readByte(uint8_t& data);
+
+public:
+ I2C();
+ uint8_t error();
+
+// master side //
+
+ void send(uint8_t address, uint8_t data);
+ void send(uint8_t address, uint8_t* data, int length);
+ void get(uint8_t address, uint8_t* data, int length);
+
+// slave side //
+
+ void setSlaveAdress(uint8_t address);
+ bool isAction();
+ bool isActionSend(); // true if master sent something
+ bool isActionGet(); // true if master wants to get something
+ int receive(uint8_t* data); // if action is send, receive the bytes
+ void returnBytes(uint8_t* data, int len, bool lastOne);
+};
+
+
+
+
+
+
+#endif
+
diff --git a/source/AVR_Studio/Soccer/hal/keylcd.c b/source/AVR_Studio/Soccer/hal/keylcd.c
new file mode 100755
index 0000000..fb2efa6
--- /dev/null
+++ b/source/AVR_Studio/Soccer/hal/keylcd.c
@@ -0,0 +1,28 @@
+#include "keylcd.h"
+
+KeyLCD::KeyLCD() : i2c() {
+
+}
+
+KeyLCD::~KeyLCD() {
+
+}
+
+// Gibt Daten auf dem keyLCD aus
+void KeyLCD::print(char *data) {
+ int len=strlen(data);
+ uint8_t buf[len+1];
+
+ for (int i=0; i<len; i++) buf[i] = uint8_t(data[i]);
+
+ i2c.send(I2C_KEYLCD, buf, len);
+}
+
+// Löscht das keyLCD
+void KeyLCD::clear() {
+
+}
+
+uint8_t KeyLCD::error() {
+ return i2c.error();
+}
diff --git a/source/AVR_Studio/Soccer/hal/keylcd.h b/source/AVR_Studio/Soccer/hal/keylcd.h
new file mode 100755
index 0000000..590c0cb
--- /dev/null
+++ b/source/AVR_Studio/Soccer/hal/keylcd.h
@@ -0,0 +1,25 @@
+#ifndef _KEYLCD_H_
+#define _KEYLCD_H_
+
+#include "i2c.h"
+#include "string.h"
+
+#define I2C_KEYLCD 2
+#define LCD_CMD_PRINTSTR 0
+
+class KeyLCD
+{
+private:
+ I2C i2c;
+public:
+ KeyLCD();
+ ~KeyLCD();
+
+ void print(char* data);
+ uint8_t error();
+ void clear();
+};
+
+#endif
+
+
diff --git a/source/AVR_Studio/Soccer/hal/uart.c b/source/AVR_Studio/Soccer/hal/uart.c
new file mode 100755
index 0000000..d8ba382
--- /dev/null
+++ b/source/AVR_Studio/Soccer/hal/uart.c
@@ -0,0 +1,585 @@
+/*************************************************************************
+Title: Interrupt UART library with receive/transmit circular buffers
+Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
+File: $Id: uart.c,v 1.5.2.10 2005/11/15 19:49:12 peter Exp $
+Software: AVR-GCC 3.3
+Hardware: any AVR with built-in UART,
+ tested on AT90S8515 at 4 Mhz and ATmega at 1Mhz
+
+DESCRIPTION:
+ An interrupt is generated when the UART has finished transmitting or
+ receiving a byte. The interrupt handling routines use circular buffers
+ for buffering received and transmitted data.
+
+ The UART_RX_BUFFER_SIZE and UART_TX_BUFFER_SIZE variables define
+ the buffer size in bytes. Note that these variables must be a
+ power of 2.
+
+USAGE:
+ Refere to the header file uart.h for a description of the routines.
+ See also example test_uart.c.
+
+NOTES:
+ Based on Atmel Application Note AVR306
+
+*************************************************************************/
+#include <avr/io.h>
+#include <avr/interrupt.h>
+//#include <avr/signal.h>
+#include <avr/pgmspace.h>
+#include "uart.h"
+
+
+/*
+ * constants and macros
+ */
+
+/* size of RX/TX buffers */
+#define UART_RX_BUFFER_MASK ( UART_RX_BUFFER_SIZE - 1)
+#define UART_TX_BUFFER_MASK ( UART_TX_BUFFER_SIZE - 1)
+
+#if ( UART_RX_BUFFER_SIZE & UART_RX_BUFFER_MASK )
+#error RX buffer size is not a power of 2
+#endif
+#if ( UART_TX_BUFFER_SIZE & UART_TX_BUFFER_MASK )
+#error TX buffer size is not a power of 2
+#endif
+
+#if defined(__AVR_AT90S2313__) \
+ || defined(__AVR_AT90S4414__) || defined(__AVR_AT90S4434__) \
+ || defined(__AVR_AT90S8515__) || defined(__AVR_AT90S8535__) \
+ || defined(__AVR_ATmega103__)
+ /* old AVR classic or ATmega103 with one UART */
+ #define AT90_UART
+ #define UART0_RECEIVE_INTERRUPT SIG_UART_RECV
+ #define UART0_TRANSMIT_INTERRUPT SIG_UART_DATA
+ #define UART0_STATUS USR
+ #define UART0_CONTROL UCR
+ #define UART0_DATA UDR
+ #define UART0_UDRIE UDRIE
+#elif defined(__AVR_AT90S2333__) || defined(__AVR_AT90S4433__)
+ /* old AVR classic with one UART */
+ #define AT90_UART
+ #define UART0_RECEIVE_INTERRUPT SIG_UART_RECV
+ #define UART0_TRANSMIT_INTERRUPT SIG_UART_DATA
+ #define UART0_STATUS UCSRA
+ #define UART0_CONTROL UCSRB
+ #define UART0_DATA UDR
+ #define UART0_UDRIE UDRIE
+#elif defined(__AVR_ATmega8__) || defined(__AVR_ATmega16__) || defined(__AVR_ATmega32__) \
+ || defined(__AVR_ATmega8515__) || defined(__AVR_ATmega8535__) \
+ || defined(__AVR_ATmega323__)
+ /* ATmega with one USART */
+ #define ATMEGA_USART
+ #define UART0_RECEIVE_INTERRUPT SIG_UART_RECV
+ #define UART0_TRANSMIT_INTERRUPT SIG_UART_DATA
+ #define UART0_STATUS UCSRA
+ #define UART0_CONTROL UCSRB
+ #define UART0_DATA UDR
+ #define UART0_UDRIE UDRIE
+#elif defined(__AVR_ATmega163__)
+ /* ATmega163 with one UART */
+ #define ATMEGA_UART
+ #define UART0_RECEIVE_INTERRUPT SIG_UART_RECV
+ #define UART0_TRANSMIT_INTERRUPT SIG_UART_DATA
+ #define UART0_STATUS UCSRA
+ #define UART0_CONTROL UCSRB
+ #define UART0_DATA UDR
+ #define UART0_UDRIE UDRIE
+#elif defined(__AVR_ATmega162__)
+ /* ATmega with two USART */
+ #define ATMEGA_USART0
+ #define ATMEGA_USART1
+ #define UART0_RECEIVE_INTERRUPT SIG_USART0_RECV
+ #define UART1_RECEIVE_INTERRUPT SIG_USART1_RECV
+ #define UART0_TRANSMIT_INTERRUPT SIG_USART0_DATA
+ #define UART1_TRANSMIT_INTERRUPT SIG_USART1_DATA
+ #define UART0_STATUS UCSR0A
+ #define UART0_CONTROL UCSR0B
+ #define UART0_DATA UDR0
+ #define UART0_UDRIE UDRIE0
+ #define UART1_STATUS UCSR1A
+ #define UART1_CONTROL UCSR1B
+ #define UART1_DATA UDR1
+ #define UART1_UDRIE UDRIE1
+#elif defined(__AVR_ATmega64__) || defined(__AVR_ATmega128__)
+ /* ATmega with two USART */
+ #define ATMEGA_USART0
+ #define ATMEGA_USART1
+ #define UART0_RECEIVE_INTERRUPT SIG_UART0_RECV
+ #define UART1_RECEIVE_INTERRUPT SIG_UART1_RECV
+ #define UART0_TRANSMIT_INTERRUPT SIG_UART0_DATA
+ #define UART1_TRANSMIT_INTERRUPT SIG_UART1_DATA
+ #define UART0_STATUS UCSR0A
+ #define UART0_CONTROL UCSR0B
+ #define UART0_DATA UDR0
+ #define UART0_UDRIE UDRIE0
+ #define UART1_STATUS UCSR1A
+ #define UART1_CONTROL UCSR1B
+ #define UART1_DATA UDR1
+ #define UART1_UDRIE UDRIE1
+#elif defined(__AVR_ATmega161__)
+ /* ATmega with UART */
+ #error "AVR ATmega161 currently not supported by this libaray !"
+#elif defined(__AVR_ATmega169__)
+ /* ATmega with one USART */
+ #define ATMEGA_USART
+ #define UART0_RECEIVE_INTERRUPT SIG_USART_RECV
+ #define UART0_TRANSMIT_INTERRUPT SIG_USART_DATA
+ #define UART0_STATUS UCSRA
+ #define UART0_CONTROL UCSRB
+ #define UART0_DATA UDR
+ #define UART0_UDRIE UDRIE
+#elif defined(__AVR_ATmega48__) ||defined(__AVR_ATmega88__) || defined(__AVR_ATmega168__)
+ #define ATMEGA_USART0
+ #define UART0_RECEIVE_INTERRUPT SIG_USART_RECV
+ #define UART0_TRANSMIT_INTERRUPT SIG_USART_DATA
+ #define UART0_STATUS UCSR0A
+ #define UART0_CONTROL UCSR0B
+ #define UART0_DATA UDR0
+ #define UART0_UDRIE UDRIE0
+#elif defined(__AVR_ATtiny2313__)
+ #define ATMEGA_USART
+ #define UART0_RECEIVE_INTERRUPT SIG_USART0_RX
+ #define UART0_TRANSMIT_INTERRUPT SIG_USART0_UDRE
+ #define UART0_STATUS UCSRA
+ #define UART0_CONTROL UCSRB
+ #define UART0_DATA UDR
+ #define UART0_UDRIE UDRIE
+#else
+ #error "no UART definition for MCU available"
+#endif
+
+
+/*
+ * module global variables
+ */
+static volatile unsigned char UART_TxBuf[UART_TX_BUFFER_SIZE];
+static volatile unsigned char UART_RxBuf[UART_RX_BUFFER_SIZE];
+static volatile unsigned char UART_TxHead;
+static volatile unsigned char UART_TxTail;
+static volatile unsigned char UART_RxHead;
+static volatile unsigned char UART_RxTail;
+static volatile unsigned char UART_LastRxError;
+
+#if defined( ATMEGA_USART1 )
+static volatile unsigned char UART1_TxBuf[UART_TX_BUFFER_SIZE];
+static volatile unsigned char UART1_RxBuf[UART_RX_BUFFER_SIZE];
+static volatile unsigned char UART1_TxHead;
+static volatile unsigned char UART1_TxTail;
+static volatile unsigned char UART1_RxHead;
+static volatile unsigned char UART1_RxTail;
+static volatile unsigned char UART1_LastRxError;
+#endif
+
+
+
+SIGNAL(UART0_RECEIVE_INTERRUPT)
+/*************************************************************************
+Function: UART Receive Complete interrupt
+Purpose: called when the UART has received a character
+**************************************************************************/
+{
+ unsigned char tmphead;
+ unsigned char data;
+ unsigned char usr;
+ unsigned char lastRxError;
+
+
+ /* read UART status register and UART data register */
+ usr = UART0_STATUS;
+ data = UART0_DATA;
+
+ /* */
+#if defined( AT90_UART )
+ lastRxError = (usr & (_BV(FE)|_BV(DOR)) );
+#elif defined( ATMEGA_USART )
+ lastRxError = (usr & (_BV(FE)|_BV(DOR)) );
+#elif defined( ATMEGA_USART0 )
+ lastRxError = (usr & (_BV(FE0)|_BV(DOR0)) );
+#elif defined ( ATMEGA_UART )
+ lastRxError = (usr & (_BV(FE)|_BV(DOR)) );
+#endif
+
+ /* calculate buffer index */
+ tmphead = ( UART_RxHead + 1) & UART_RX_BUFFER_MASK;
+
+ if ( tmphead == UART_RxTail ) {
+ /* error: receive buffer overflow */
+ lastRxError = UART_BUFFER_OVERFLOW >> 8;
+ }else{
+ /* store new index */
+ UART_RxHead = tmphead;
+ /* store received data in buffer */
+ UART_RxBuf[tmphead] = data;
+ }
+ UART_LastRxError = lastRxError;
+}
+
+
+SIGNAL(UART0_TRANSMIT_INTERRUPT)
+/*************************************************************************
+Function: UART Data Register Empty interrupt
+Purpose: called when the UART is ready to transmit the next byte
+**************************************************************************/
+{
+ unsigned char tmptail;
+
+
+ if ( UART_TxHead != UART_TxTail) {
+ /* calculate and store new buffer index */
+ tmptail = (UART_TxTail + 1) & UART_TX_BUFFER_MASK;
+ UART_TxTail = tmptail;
+ /* get one byte from buffer and write it to UART */
+ UART0_DATA = UART_TxBuf[tmptail]; /* start transmission */
+ }else{
+ /* tx buffer empty, disable UDRE interrupt */
+ UART0_CONTROL &= ~_BV(UART0_UDRIE);
+ }
+}
+
+
+/*************************************************************************
+Function: uart_init()
+Purpose: initialize UART and set baudrate
+Input: baudrate using macro UART_BAUD_SELECT()
+Returns: none
+**************************************************************************/
+void uart_init(unsigned int baudrate)
+{
+ UART_TxHead = 0;
+ UART_TxTail = 0;
+ UART_RxHead = 0;
+ UART_RxTail = 0;
+
+#if defined( AT90_UART )
+ /* set baud rate */
+ UBRR = (unsigned char)baudrate;
+
+ /* enable UART receiver and transmmitter and receive complete interrupt */
+ UART0_CONTROL = _BV(RXCIE)|_BV(RXEN)|_BV(TXEN);
+
+#elif defined (ATMEGA_USART)
+ /* Set baud rate */
+ if ( baudrate & 0x8000 )
+ {
+ UART0_STATUS = (1<<U2X); //Enable 2x speed
+ baudrate &= ~0x8000;
+ }
+ UBRRH = (unsigned char)(baudrate>>8);
+ UBRRL = (unsigned char) baudrate;
+
+ /* Enable USART receiver and transmitter and receive complete interrupt */
+ UART0_CONTROL = _BV(RXCIE)|(1<<RXEN)|(1<<TXEN);
+
+ /* Set frame format: asynchronous, 8data, no parity, 1stop bit */
+ #ifdef URSEL
+ UCSRC = (1<<URSEL)|(3<<UCSZ0);
+ #else
+ UCSRC = (3<<UCSZ0);
+ #endif
+
+#elif defined (ATMEGA_USART0 )
+ /* Set baud rate */
+ if ( baudrate & 0x8000 )
+ {
+ UART0_STATUS = (1<<U2X0); //Enable 2x speed
+ baudrate &= ~0x8000;
+ }
+ UBRR0H = (unsigned char)(baudrate>>8);
+ UBRR0L = (unsigned char) baudrate;
+
+ /* Enable USART receiver and transmitter and receive complete interrupt */
+ UART0_CONTROL = _BV(RXCIE0)|(1<<RXEN0)|(1<<TXEN0);
+
+ /* Set frame format: asynchronous, 8data, no parity, 1stop bit */
+ #ifdef URSEL0
+ UCSR0C = (1<<URSEL0)|(3<<UCSZ00);
+ #else
+ UCSR0C = (3<<UCSZ00);
+ #endif
+
+#elif defined ( ATMEGA_UART )
+ /* set baud rate */
+ if ( baudrate & 0x8000 )
+ {
+ UART0_STATUS = (1<<U2X); //Enable 2x speed
+ baudrate &= ~0x8000;
+ }
+ UBRRHI = (unsigned char)(baudrate>>8);
+ UBRR = (unsigned char) baudrate;
+
+ /* Enable UART receiver and transmitter and receive complete interrupt */
+ UART0_CONTROL = _BV(RXCIE)|(1<<RXEN)|(1<<TXEN);
+
+#endif
+
+}/* uart_init */
+
+
+/*************************************************************************
+Function: uart_getc()
+Purpose: return byte from ringbuffer
+Returns: lower byte: received byte from ringbuffer
+ higher byte: last receive error
+**************************************************************************/
+unsigned int uart_getc(void)
+{
+ unsigned char tmptail;
+ unsigned char data;
+
+
+ if ( UART_RxHead == UART_RxTail ) {
+ return UART_NO_DATA; /* no data available */
+ }
+
+ /* calculate /store buffer index */
+ tmptail = (UART_RxTail + 1) & UART_RX_BUFFER_MASK;
+ UART_RxTail = tmptail;
+
+ /* get data from receive buffer */
+ data = UART_RxBuf[tmptail];
+
+ return (UART_LastRxError << 8) + data;
+
+}/* uart_getc */
+
+
+/*************************************************************************
+Function: uart_putc()
+Purpose: write byte to ringbuffer for transmitting via UART
+Input: byte to be transmitted
+Returns: none
+**************************************************************************/
+void uart_putc(unsigned char data)
+{
+ unsigned char tmphead;
+
+
+ tmphead = (UART_TxHead + 1) & UART_TX_BUFFER_MASK;
+
+ while ( tmphead == UART_TxTail ){
+ ;/* wait for free space in buffer */
+ }
+
+ UART_TxBuf[tmphead] = data;
+ UART_TxHead = tmphead;
+
+ /* enable UDRE interrupt */
+ UART0_CONTROL |= _BV(UART0_UDRIE);
+
+}/* uart_putc */
+
+
+/*************************************************************************
+Function: uart_puts()
+Purpose: transmit string to UART
+Input: string to be transmitted
+Returns: none
+**************************************************************************/
+void uart_puts(const char *s )
+{
+ while (*s)
+ uart_putc(*s++);
+
+}/* uart_puts */
+
+
+/*************************************************************************
+Function: uart_puts_p()
+Purpose: transmit string from program memory to UART
+Input: program memory string to be transmitted
+Returns: none
+**************************************************************************/
+void uart_puts_p(const char *progmem_s )
+{
+ register char c;
+
+ while ( (c = pgm_read_byte(progmem_s++)) )
+ uart_putc(c);
+
+}/* uart_puts_p */
+
+
+/*
+ * these functions are only for ATmegas with two USART
+ */
+#if defined( ATMEGA_USART1 )
+
+SIGNAL(UART1_RECEIVE_INTERRUPT)
+/*************************************************************************
+Function: UART1 Receive Complete interrupt
+Purpose: called when the UART1 has received a character
+**************************************************************************/
+{
+ unsigned char tmphead;
+ unsigned char data;
+ unsigned char usr;
+ unsigned char lastRxError;
+
+
+ /* read UART status register and UART data register */
+ usr = UART1_STATUS;
+ data = UART1_DATA;
+
+ /* */
+ lastRxError = (usr & (_BV(FE1)|_BV(DOR1)) );
+
+ /* calculate buffer index */
+ tmphead = ( UART1_RxHead + 1) & UART_RX_BUFFER_MASK;
+
+ if ( tmphead == UART1_RxTail ) {
+ /* error: receive buffer overflow */
+ lastRxError = UART_BUFFER_OVERFLOW >> 8;
+ }else{
+ /* store new index */
+ UART1_RxHead = tmphead;
+ /* store received data in buffer */
+ UART1_RxBuf[tmphead] = data;
+ }
+ UART1_LastRxError = lastRxError;
+}
+
+
+SIGNAL(UART1_TRANSMIT_INTERRUPT)
+/*************************************************************************
+Function: UART1 Data Register Empty interrupt
+Purpose: called when the UART1 is ready to transmit the next byte
+**************************************************************************/
+{
+ unsigned char tmptail;
+
+
+ if ( UART1_TxHead != UART1_TxTail) {
+ /* calculate and store new buffer index */
+ tmptail = (UART1_TxTail + 1) & UART_TX_BUFFER_MASK;
+ UART1_TxTail = tmptail;
+ /* get one byte from buffer and write it to UART */
+ UART1_DATA = UART1_TxBuf[tmptail]; /* start transmission */
+ }else{
+ /* tx buffer empty, disable UDRE interrupt */
+ UART1_CONTROL &= ~_BV(UART1_UDRIE);
+ }
+}
+
+
+/*************************************************************************
+Function: uart1_init()
+Purpose: initialize UART1 and set baudrate
+Input: baudrate using macro UART_BAUD_SELECT()
+Returns: none
+**************************************************************************/
+void uart1_init(unsigned int baudrate)
+{
+ UART1_TxHead = 0;
+ UART1_TxTail = 0;
+ UART1_RxHead = 0;
+ UART1_RxTail = 0;
+
+
+ /* Set baud rate */
+ if ( baudrate & 0x8000 )
+ {
+ UART1_STATUS = (1<<U2X1); //Enable 2x speed
+ baudrate &= ~0x8000;
+ }
+ UBRR1H = (unsigned char)(baudrate>>8);
+ UBRR1L = (unsigned char) baudrate;
+
+ /* Enable USART receiver and transmitter and receive complete interrupt */
+ UART1_CONTROL = _BV(RXCIE1)|(1<<RXEN1)|(1<<TXEN1);
+
+ /* Set frame format: asynchronous, 8data, no parity, 1stop bit */
+ #ifdef URSEL1
+ UCSR1C = (1<<URSEL1)|(3<<UCSZ10);
+ #else
+ UCSR1C = (3<<UCSZ10);
+ #endif
+}/* uart_init */
+
+
+/*************************************************************************
+Function: uart1_getc()
+Purpose: return byte from ringbuffer
+Returns: lower byte: received byte from ringbuffer
+ higher byte: last receive error
+**************************************************************************/
+unsigned int uart1_getc(void)
+{
+ unsigned char tmptail;
+ unsigned char data;
+
+
+ if ( UART1_RxHead == UART1_RxTail ) {
+ return UART_NO_DATA; /* no data available */
+ }
+
+ /* calculate /store buffer index */
+ tmptail = (UART1_RxTail + 1) & UART_RX_BUFFER_MASK;
+ UART1_RxTail = tmptail;
+
+ /* get data from receive buffer */
+ data = UART1_RxBuf[tmptail];
+
+ return (UART1_LastRxError << 8) + data;
+
+}/* uart1_getc */
+
+
+/*************************************************************************
+Function: uart1_putc()
+Purpose: write byte to ringbuffer for transmitting via UART
+Input: byte to be transmitted
+Returns: none
+**************************************************************************/
+void uart1_putc(unsigned char data)
+{
+ unsigned char tmphead;
+
+
+ tmphead = (UART1_TxHead + 1) & UART_TX_BUFFER_MASK;
+
+ while ( tmphead == UART1_TxTail ){
+ ;/* wait for free space in buffer */
+ }
+
+ UART1_TxBuf[tmphead] = data;
+ UART1_TxHead = tmphead;
+
+ /* enable UDRE interrupt */
+ UART1_CONTROL |= _BV(UART1_UDRIE);
+
+}/* uart1_putc */
+
+
+/*************************************************************************
+Function: uart1_puts()
+Purpose: transmit string to UART1
+Input: string to be transmitted
+Returns: none
+**************************************************************************/
+void uart1_puts(const char *s )
+{
+ while (*s)
+ uart1_putc(*s++);
+
+}/* uart1_puts */
+
+
+/*************************************************************************
+Function: uart1_puts_p()
+Purpose: transmit string from program memory to UART1
+Input: program memory string to be transmitted
+Returns: none
+**************************************************************************/
+void uart1_puts_p(const char *progmem_s )
+{
+ register char c;
+
+ while ( (c = pgm_read_byte(progmem_s++)) )
+ uart1_putc(c);
+
+}/* uart1_puts_p */
+
+
+#endif
diff --git a/source/AVR_Studio/Soccer/hal/uart.h b/source/AVR_Studio/Soccer/hal/uart.h
new file mode 100755
index 0000000..14e26f6
--- /dev/null
+++ b/source/AVR_Studio/Soccer/hal/uart.h
@@ -0,0 +1,179 @@
+#ifndef UART_H
+#define UART_H
+/************************************************************************
+Title: Interrupt UART library with receive/transmit circular buffers
+Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
+File: $Id: uart.h,v 1.7.2.5 2005/08/14 11:25:41 Peter Exp $
+Software: AVR-GCC 3.3
+Hardware: any AVR with built-in UART, tested on AT90S8515 at 4 Mhz
+Usage: see Doxygen manual
+************************************************************************/
+
+/**
+ * @defgroup pfleury_uart UART Library
+ * @code #include <uart.h> @endcode
+ *
+ * @brief Interrupt UART library using the built-in UART with transmit and receive circular buffers.
+ *
+ * This library can be used to transmit and receive data through the built in UART.
+ *
+ * An interrupt is generated when the UART has finished transmitting or
+ * receiving a byte. The interrupt handling routines use circular buffers
+ * for buffering received and transmitted data.
+ *
+ * The UART_RX_BUFFER_SIZE and UART_TX_BUFFER_SIZE constants define
+ * the size of the circular buffers in bytes. Note that these constants must be a power of 2.
+ * You may need to adapt this constants to your target and your application by adding
+ * CDEFS += -DUART_RX_BUFFER_SIZE=nn -DUART_RX_BUFFER_SIZE=nn to your Makefile.
+ *
+ * @note Based on Atmel Application Note AVR306
+ * @author Peter Fleury pfleury@gmx.ch http://jump.to/fleury
+ */
+
+/**@{*/
+
+
+#if (__GNUC__ * 100 + __GNUC_MINOR__) < 304
+#error "This library requires AVR-GCC 3.4 or later, update to newer AVR-GCC compiler !"
+#endif
+
+
+/*
+** constants and macros
+*/
+
+/** @brief UART Baudrate Expression
+ * @param xtalcpu system clock in Mhz, e.g. 4000000L for 4Mhz
+ * @param baudrate baudrate in bps, e.g. 1200, 2400, 9600
+ */
+#define UART_BAUD_SELECT(baudRate,xtalCpu) ((xtalCpu)/((baudRate)*16l)-1)
+
+/** @brief UART Baudrate Expression for ATmega double speed mode
+ * @param xtalcpu system clock in Mhz, e.g. 4000000L for 4Mhz
+ * @param baudrate baudrate in bps, e.g. 1200, 2400, 9600
+ */
+#define UART_BAUD_SELECT_DOUBLE_SPEED(baudRate,xtalCpu) (((xtalCpu)/((baudRate)*8l)-1)|0x8000)
+
+
+/** Size of the circular receive buffer, must be power of 2 */
+#ifndef UART_RX_BUFFER_SIZE
+#define UART_RX_BUFFER_SIZE 32
+#endif
+/** Size of the circular transmit buffer, must be power of 2 */
+#ifndef UART_TX_BUFFER_SIZE
+#define UART_TX_BUFFER_SIZE 32
+#endif
+
+/* test if the size of the circular buffers fits into SRAM */
+#if ( (UART_RX_BUFFER_SIZE+UART_TX_BUFFER_SIZE) >= (RAMEND-0x60 ) )
+#error "size of UART_RX_BUFFER_SIZE + UART_TX_BUFFER_SIZE larger than size of SRAM"
+#endif
+
+/*
+** high byte error return code of uart_getc()
+*/
+#define UART_FRAME_ERROR 0x0800 /* Framing Error by UART */
+#define UART_OVERRUN_ERROR 0x0400 /* Overrun condition by UART */
+#define UART_BUFFER_OVERFLOW 0x0200 /* receive ringbuffer overflow */
+#define UART_NO_DATA 0x0100 /* no receive data available */
+
+
+/*
+** function prototypes
+*/
+
+/**
+ @brief Initialize UART and set baudrate
+ @param baudrate Specify baudrate using macro UART_BAUD_SELECT()
+ @return none
+*/
+extern void uart_init(unsigned int baudrate);
+
+
+/**
+ * @brief Get received byte from ringbuffer
+ *
+ * Returns in the lower byte the received character and in the
+ * higher byte the last receive error.
+ * UART_NO_DATA is returned when no data is available.
+ *
+ * @param void
+ * @return lower byte: received byte from ringbuffer
+ * @return higher byte: last receive status
+ * - \b 0 successfully received data from UART
+ * - \b UART_NO_DATA
+ * <br>no receive data available
+ * - \b UART_BUFFER_OVERFLOW
+ * <br>Receive ringbuffer overflow.
+ * We are not reading the receive buffer fast enough,
+ * one or more received character have been dropped
+ * - \b UART_OVERRUN_ERROR
+ * <br>Overrun condition by UART.
+ * A character already present in the UART UDR register was
+ * not read by the interrupt handler before the next character arrived,
+ * one or more received characters have been dropped.
+ * - \b UART_FRAME_ERROR
+ * <br>Framing Error by UART
+ */
+extern unsigned int uart_getc(void);
+
+
+/**
+ * @brief Put byte to ringbuffer for transmitting via UART
+ * @param data byte to be transmitted
+ * @return none
+ */
+extern void uart_putc(unsigned char data);
+
+
+/**
+ * @brief Put string to ringbuffer for transmitting via UART
+ *
+ * The string is buffered by the uart library in a circular buffer
+ * and one character at a time is transmitted to the UART using interrupts.
+ * Blocks if it can not write the whole string into the circular buffer.
+ *
+ * @param s string to be transmitted
+ * @return none
+ */
+extern void uart_puts(const char *s );
+
+
+/**
+ * @brief Put string from program memory to ringbuffer for transmitting via UART.
+ *
+ * The string is buffered by the uart library in a circular buffer
+ * and one character at a time is transmitted to the UART using interrupts.
+ * Blocks if it can not write the whole string into the circular buffer.
+ *
+ * @param s program memory string to be transmitted
+ * @return none
+ * @see uart_puts_P
+ */
+extern void uart_puts_p(const char *s );
+
+/**
+ * @brief Macro to automatically put a string constant into program memory
+ */
+#define uart_puts_P(__s) uart_puts_p(PSTR(__s))
+
+
+
+/** @brief Initialize USART1 (only available on selected ATmegas) @see uart_init */
+extern void uart1_init(unsigned int baudrate);
+/** @brief Get received byte of USART1 from ringbuffer. (only available on selected ATmega) @see uart_getc */
+extern unsigned int uart1_getc(void);
+/** @brief Put byte to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_putc */
+extern void uart1_putc(unsigned char data);
+/** @brief Put string to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_puts */
+extern void uart1_puts(const char *s );
+/** @brief Put string from program memory to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_puts_p */
+extern void uart1_puts_p(const char *s );
+/** @brief Macro to automatically put a string constant into program memory */
+#define uart1_puts_P(__s) uart1_puts_p(PSTR(__s))
+
+/**@}*/
+
+
+#endif // UART_H
+