lm3s1968: generic UART driver.
authorarighi <arighi@38d2e660-2303-0410-9eaa-f027e97ec537>
Tue, 13 Apr 2010 13:13:44 +0000 (13:13 +0000)
committerarighi <arighi@38d2e660-2303-0410-9eaa-f027e97ec537>
Tue, 13 Apr 2010 13:13:44 +0000 (13:13 +0000)
git-svn-id: https://src.develer.com/svnoss/bertos/trunk@3425 38d2e660-2303-0410-9eaa-f027e97ec537

bertos/cfg/cfg_ser.h
bertos/cpu/cortex-m3/drv/kdebug_lm3s.c
bertos/cpu/cortex-m3/drv/ser_cm3.c [new file with mode: 0644]
bertos/cpu/cortex-m3/drv/ser_cm3.h [new file with mode: 0644]
bertos/cpu/cortex-m3/drv/ser_lm3s.c [new file with mode: 0644]
bertos/cpu/cortex-m3/drv/ser_lm3s.h [new file with mode: 0644]

index 813328060ec1af41847094e238da3d318dbe76e6..dba27153e76253c6ef58df64388f0a8a835df181 100644 (file)
  */
 #define CONFIG_UART1_RXBUFSIZE  32
 
+/**
+ * Size of the outbound FIFO buffer for port 2 [bytes].
+ * $WIZ$ type = "int"
+ * $WIZ$ min = 2
+ * $WIZ$ supports = "lm3s"
+ */
+#define CONFIG_UART2_TXBUFSIZE  32
+
+/**
+ * Size of the inbound FIFO buffer for port 2 [bytes].
+ * $WIZ$ type = "int"
+ * $WIZ$ min = 2
+ * $WIZ$ supports = "lm3s"
+ */
+#define CONFIG_UART2_RXBUFSIZE  32
+
 
 /**
  * Size of the outbound FIFO buffer for SPI port [bytes].
index 65c1dccb46512e36ccc917ee349840dccf6355a7..c76ab8ec974b6f12946afbfe143d74effedd2de3 100644 (file)
 #include <drv/clock_lm3s.h> /* lm3s_busyWait() */
 #include <drv/gpio_lm3s.h>
 #include <io/lm3s.h>
+#include <drv/ser_lm3s.h>
 #include "kdebug_lm3s.h"
 
-INLINE void uart_disable(size_t base)
-{
-       /* Disable the FIFO */
-       HWREG(base + UART_O_LCRH) &= ~UART_LCRH_FEN;
-       /* Disable the UART */
-       HWREG(base + UART_O_CTL) &=
-               ~(UART_CTL_UARTEN | UART_CTL_TXE | UART_CTL_RXE);
-}
-
-INLINE void uart_enable(size_t base)
-{
-       /* Enable the FIFO */
-       HWREG(base + UART_O_LCRH) |= UART_LCRH_FEN;
-       /* Enable RX, TX, and the UART */
-       HWREG(base + UART_O_CTL) |=
-                       UART_CTL_UARTEN | UART_CTL_TXE | UART_CTL_RXE;
-}
-
-INLINE void uart_config(size_t base, uint32_t baud, reg32_t config)
-{
-       unsigned long div;
-       bool hi_speed;
-
-       if (baud * 16 > CPU_FREQ)
-       {
-               hi_speed = true;
-               baud /= 2;
-       }
-       div = (CPU_FREQ * 8 / baud + 1) / 2;
-
-       uart_disable(base);
-
-       if (hi_speed)
-               HWREG(base + UART_O_CTL) |= UART_CTL_HSE;
-       else
-               HWREG(base + UART_O_CTL) &= ~UART_CTL_HSE;
-
-       /* Set the baud rate */
-       HWREG(base + UART_O_IBRD) = div / 64;
-       HWREG(base + UART_O_FBRD) = div % 64;
-
-       /* Set parity, data length, and number of stop bits. */
-       HWREG(base + UART_O_LCRH) = config;
-
-       /* Clear the flags register */
-       HWREG(base + UART_O_FR) = 0;
-
-       uart_enable(base);
-}
+#if CONFIG_KDEBUG_PORT == KDEBUG_PORT_DBGU
 
-INLINE bool uart_putchar(size_t base, unsigned char ch)
-{
-       if (!(HWREG(base + UART_O_FR) & UART_FR_TXFF))
-       {
-               HWREG(base + UART_O_DR) = ch;
-               return true;
-       }
-       return false;
-}
+#if CONFIG_KDEBUG_PORT == 0
+       #define UART_BASE UART0_BASE
+#elif CONFIG_KDEBUG_PORT == 1
+       #define UART_BASE UART1_BASE
+#elif CONFIG_KDEBUG_PORT == 2
+       #define UART_BASE UART2_BASE
+#else
+       #error "UART port not supported in this board"
+#endif
 
-#if CONFIG_KDEBUG_PORT == KDEBUG_PORT_DBGU
-#define KDBG_WAIT_READY()     while (HWREG(UART0_BASE + UART_O_FR) & UART_FR_BUSY) {}
-#define KDBG_WAIT_TXDONE()    while (!(HWREG(UART0_BASE + UART_O_FR) & UART_FR_TXFE)) {}
+#define KDBG_WAIT_READY()     while (!lm3s_uartReady(UART_BASE)) {}
+#define KDBG_WAIT_TXDONE()    while (!lm3s_uartTxDone(UART_BASE)) {}
 
-#define KDBG_WRITE_CHAR(c)    do { HWREG(UART0_BASE + UART_O_DR) = c; } while(0)
+#define KDBG_WRITE_CHAR(c)    do { lm3s_uartPutCharNonBlocking(UART_BASE, c); } while(0)
 
 /* Debug unit is used only for debug purposes so does not generate interrupts. */
 #define KDBG_MASK_IRQ(old)    do { (void)old; } while(0)
@@ -122,14 +74,6 @@ typedef uint32_t kdbg_irqsave_t;
 
 INLINE void kdbg_hw_init(void)
 {
-       /* Enable the peripheral clock */
-       SYSCTL_RCGC1_R |= SYSCTL_RCGC1_UART0;
-       SYSCTL_RCGC2_R |= SYSCTL_RCGC2_GPIOA;
-       lm3s_busyWait(512);
-
-       /* Set GPIO A0 and A1 as UART pins */
-       lm3s_gpioPinConfig(GPIO_PORTA_BASE, BV(0) | BV(1),
-                       GPIO_DIR_MODE_HW, GPIO_STRENGTH_2MA, GPIO_PIN_TYPE_STD);
-       /* 115.200, 8-bit word, no parity, one stop bit */
-       uart_config(UART0_BASE, CONFIG_KDEBUG_BAUDRATE, UART_LCRH_WLEN_8);
+       /* Initialize UART0 */
+       lm3s_uartInit(CONFIG_KDEBUG_PORT);
 }
diff --git a/bertos/cpu/cortex-m3/drv/ser_cm3.c b/bertos/cpu/cortex-m3/drv/ser_cm3.c
new file mode 100644 (file)
index 0000000..06aee36
--- /dev/null
@@ -0,0 +1,45 @@
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction.  Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License.  This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \brief Low-level serial module for Cortex-M3 (interface).
+ *
+ * \author Andrea Righi <arighi@develer.com>
+ */
+
+#include <cpu/detect.h>
+
+#if CPU_CM3_LM3S
+       #include "ser_lm3s.c"
+/*#elif  Add other Cortex-M3 CPUs here */
+#else
+       #error Unknown CPU
+#endif
diff --git a/bertos/cpu/cortex-m3/drv/ser_cm3.h b/bertos/cpu/cortex-m3/drv/ser_cm3.h
new file mode 100644 (file)
index 0000000..7268711
--- /dev/null
@@ -0,0 +1,45 @@
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction.  Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License.  This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \brief Low-level serial module for Cortex-M3 (interface).
+ *
+ * \author Andrea Righi <arighi@develer.com>
+ */
+
+#include <cpu/detect.h>
+
+#if CPU_CM3_LM3S
+       #include "ser_lm3s.h"
+/*#elif  Add other Cortex-M3 CPUs here */
+#else
+       #error Unknown CPU
+#endif
diff --git a/bertos/cpu/cortex-m3/drv/ser_lm3s.c b/bertos/cpu/cortex-m3/drv/ser_lm3s.c
new file mode 100644 (file)
index 0000000..d24094d
--- /dev/null
@@ -0,0 +1,342 @@
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction.  Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License.  This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \brief LM3S1968 UART interface driver.
+ *
+ * \author Andrea Righi <arighi@develer.com>
+ */
+
+#include <cfg/macros.h> /* for BV() */
+#include <drv/clock_lm3s.h> /* lm3s_busyWait() */
+#include <drv/gpio_lm3s.h>
+#include <drv/ser_p.h>
+#include <drv/ser.h>
+#include <drv/irq_cm3.h>
+#include "cfg/cfg_ser.h"
+#include "ser_lm3s.h"
+
+/* From the high-level serial driver */
+extern struct Serial *ser_handles[SER_CNT];
+
+struct CM3Serial
+{
+       struct SerialHardware hw;
+       bool sending;
+       uint32_t base;
+       sysirq_t irq;
+};
+
+/* Forward declaration */
+static struct CM3Serial UARTDesc[SER_CNT];
+
+/* Clear the flags register */
+INLINE void lm3s_uartClear(uint32_t base)
+{
+       HWREG(base + UART_O_FR) = 0;
+}
+
+void lm3s_uartSetBaudRate(uint32_t base, unsigned long baud)
+{
+       unsigned long div;
+       bool hi_speed;
+
+       if (baud * 16 > CPU_FREQ)
+       {
+               hi_speed = true;
+               baud /= 2;
+       }
+       div = (CPU_FREQ * 8 / baud + 1) / 2;
+
+       lm3s_uartDisable(base);
+       if (hi_speed)
+               HWREG(base + UART_O_CTL) |= UART_CTL_HSE;
+       else
+               HWREG(base + UART_O_CTL) &= ~UART_CTL_HSE;
+       /* Set the baud rate */
+       HWREG(base + UART_O_IBRD) = div / 64;
+       HWREG(base + UART_O_FBRD) = div % 64;
+       lm3s_uartClear(base);
+       lm3s_uartEnable(base);
+}
+
+void lm3s_uartSetParity(uint32_t base, int parity)
+{
+       /* Set 8-bit word, one stop bit by default */
+       uint32_t config = UART_LCRH_WLEN_8;
+
+       switch(parity)
+       {
+       case SER_PARITY_NONE:
+               break;
+       case SER_PARITY_ODD:
+               config |= UART_LCRH_PEN;
+               break;
+       case SER_PARITY_EVEN:
+               config |= UART_LCRH_EPS | UART_LCRH_PEN;
+               break;
+       default:
+               ASSERT(0);
+               return;
+       }
+       lm3s_uartDisable(base);
+       HWREG(base + UART_O_LCRH) = config;
+       lm3s_uartClear(base);
+       lm3s_uartEnable(base);
+}
+
+void lm3s_uartInit(int port)
+{
+       uint32_t reg_clock, base;
+
+       ASSERT(port >= 0 && port < SER_CNT);
+
+       base = UARTDesc[port].base;
+       reg_clock = 1 << port;
+
+       /* Enable the peripheral clock */
+       SYSCTL_RCGC1_R |= reg_clock;
+       SYSCTL_RCGC2_R |= SYSCTL_RCGC2_GPIOA;
+       lm3s_busyWait(512);
+
+       /* Set GPIO A0 and A1 as UART pins */
+       lm3s_gpioPinConfig(GPIO_PORTA_BASE, BV(0) | BV(1),
+                       GPIO_DIR_MODE_HW, GPIO_STRENGTH_2MA, GPIO_PIN_TYPE_STD);
+
+       /* Set serial param: 115.200 bps, no parity */
+       lm3s_uartSetBaudRate(base, 115200);
+       lm3s_uartSetParity(base, SER_PARITY_NONE);
+}
+
+static bool tx_sending(struct SerialHardware *_hw)
+{
+       struct CM3Serial *hw = (struct CM3Serial *)_hw;
+       return hw->sending;
+}
+
+static void uart_irq_rx(int port)
+{
+       struct FIFOBuffer *rxfifo = &ser_handles[port]->rxfifo;
+       uint32_t base = UARTDesc[port].base;
+       char c;
+
+       while (lm3s_uartRxReady(base))
+       {
+               c = HWREG(base + UART_O_DR);
+               if (fifo_isfull(rxfifo))
+                       ser_handles[port]->status |= SERRF_RXFIFOOVERRUN;
+               else
+                       fifo_push(rxfifo, c);
+       }
+}
+
+static void uart_irq_tx(int port)
+{
+       struct FIFOBuffer *txfifo = &ser_handles[port]->txfifo;
+       uint32_t base = UARTDesc[port].base;
+
+       while (lm3s_uartTxReady(base))
+       {
+               if (fifo_isempty(txfifo)) {
+                       /*
+                        * Disable TX empty interrupts if there're no more
+                        * characters to transmit.
+                        */
+                       HWREG(base + UART_O_IM) &= ~UART_IM_TXIM;
+                       UARTDesc[port].sending = false;
+                       break;
+               }
+               HWREG(base + UART_O_DR) = fifo_pop(txfifo);
+       }
+}
+
+static void uart_common_irq_handler(int port)
+{
+       uint32_t base = UARTDesc[port].base;
+       uint32_t status;
+
+       /* Read and clear the IRQ status */
+       status = HWREG(base + UART_O_RIS);
+
+       /* Process the IRQ */
+       if (status & (UART_RIS_RXRIS | UART_RIS_RTRIS))
+               uart_irq_rx(port);
+       if (status & UART_RIS_TXRIS)
+               uart_irq_tx(port);
+}
+
+static void
+lm3s_uartIRQEnable(int port, sysirq_handler_t handler)
+{
+       uint32_t base = UARTDesc[port].base;
+       sysirq_t irq = UARTDesc[port].irq;
+
+       /* Register the IRQ handler */
+       sysirq_setHandler(irq, handler);
+       /* Enable RX interrupt in the UART interrupt mask register */
+       HWREG(base + UART_O_IM) |= UART_IM_RXIM | UART_IM_RTIM;
+}
+
+static void lm3s_uartIRQDisable(int port)
+{
+       uint32_t base = UARTDesc[port].base;
+
+       HWREG(base + UART_O_IM) &=
+                       ~(UART_IM_TXIM | UART_IM_RXIM | UART_IM_RTIM);
+}
+
+/* UART class definition */
+#define UART_PORT(port)                                                                \
+       /* UART TX and RX buffers */                                            \
+       static unsigned char                                                    \
+               uart ## port ## _txbuffer[CONFIG_UART ## port ## _TXBUFSIZE];   \
+       static unsigned char                                                    \
+               uart ## port ## _rxbuffer[CONFIG_UART ## port ## _RXBUFSIZE];   \
+                                                                               \
+       /* UART interrupt handler */                                            \
+       static DECLARE_ISR(uart ## port ## _irq_handler)                        \
+       {                                                                       \
+               uart_common_irq_handler(port);                                  \
+       }                                                                       \
+                                                                               \
+       /* UART public methods */                                               \
+       static void                                                             \
+       uart ## port ## _txStart(struct SerialHardware *_hw)                    \
+       {                                                                       \
+               struct FIFOBuffer *txfifo = &ser_handles[port]->txfifo;         \
+               struct CM3Serial *hw = (struct CM3Serial *)_hw;                 \
+                                                                               \
+                if (hw->sending)                                               \
+                        return;                                                        \
+               lm3s_uartPutChar(UART ## port ## _BASE, fifo_pop(txfifo));      \
+               if (!fifo_isempty(txfifo))                                      \
+               {                                                               \
+                       HWREG(UART ## port ## _BASE + UART_O_IM) |=             \
+                                                UART_IM_TXIM;                  \
+                       hw->sending = true;                                     \
+               }                                                               \
+       }                                                                       \
+                                                                               \
+       static void                                                             \
+       uart ## port ## _setbaudrate(UNUSED_ARG(struct SerialHardware *, hw),   \
+                                               unsigned long baud)             \
+       {                                                                       \
+               lm3s_uartSetBaudRate(UART ## port ## _BASE, baud);              \
+       }                                                                       \
+                                                                               \
+       static void                                                             \
+       uart ## port ## _setparity(UNUSED_ARG(struct SerialHardware *, hw),     \
+                                               int parity)                     \
+       {                                                                       \
+               lm3s_uartSetParity(UART ## port ## _BASE, parity);              \
+       }                                                                       \
+                                                                               \
+       static void                                                             \
+       uart ## port ## _cleanup(struct SerialHardware *_hw)                    \
+       {                                                                       \
+               struct CM3Serial *hw = (struct CM3Serial *)_hw;                 \
+                                                                               \
+               hw->sending = false;                                            \
+               lm3s_uartIRQDisable(port);                                      \
+               lm3s_uartClear(UART ## port ## _BASE);                          \
+               lm3s_uartDisable(UART ## port ## _BASE);                        \
+       }                                                                       \
+                                                                               \
+       static void                                                             \
+       uart ## port ## _init(UNUSED_ARG(struct SerialHardware *, hw),          \
+                               UNUSED_ARG(struct Serial *, ser))               \
+       {                                                                       \
+               lm3s_uartInit(port);                                            \
+               lm3s_uartEnable(UART ## port ## _BASE);                         \
+               lm3s_uartIRQEnable(port, uart ## port ## _irq_handler);         \
+       }                                                                       \
+                                                                               \
+       /* UART operations */                                                   \
+       static const struct SerialHardwareVT UART ## port ## _VT =              \
+       {                                                                       \
+               .init = uart ## port ## _init,                                  \
+               .cleanup = uart ## port ## _cleanup,                            \
+               .setBaudrate = uart ## port ## _setbaudrate,                    \
+               .setParity = uart ## port ## _setparity,                        \
+               .txStart = uart ## port ## _txStart,                            \
+               .txSending = tx_sending,                                        \
+       };
+
+/* UART port instances */
+UART_PORT(0)
+UART_PORT(1)
+UART_PORT(2)
+
+static struct CM3Serial UARTDesc[SER_CNT] =
+{
+       {
+               .hw = {
+                       .table = &UART0_VT,
+                       .txbuffer = uart0_txbuffer,
+                       .rxbuffer = uart0_rxbuffer,
+                       .txbuffer_size = sizeof(uart0_txbuffer),
+                       .rxbuffer_size = sizeof(uart0_rxbuffer),
+               },
+               .sending = false,
+               .base = UART0_BASE,
+               .irq = INT_UART0,
+       },
+       {
+               .hw = {
+                       .table = &UART1_VT,
+                       .txbuffer = uart1_txbuffer,
+                       .rxbuffer = uart1_rxbuffer,
+                       .txbuffer_size = sizeof(uart1_txbuffer),
+                       .rxbuffer_size = sizeof(uart1_rxbuffer),
+               },
+               .sending = false,
+               .base = UART1_BASE,
+               .irq = INT_UART1,
+       },
+       {
+               .hw = {
+                       .table = &UART2_VT,
+                       .txbuffer = uart2_txbuffer,
+                       .rxbuffer = uart2_rxbuffer,
+                       .txbuffer_size = sizeof(uart2_txbuffer),
+                       .rxbuffer_size = sizeof(uart2_rxbuffer),
+               },
+               .sending = false,
+               .base = UART2_BASE,
+               .irq = INT_UART2,
+       },
+};
+
+struct SerialHardware *ser_hw_getdesc(int port)
+{
+       ASSERT(port >= 0 && port < SER_CNT);
+       return &UARTDesc[port].hw;
+}
diff --git a/bertos/cpu/cortex-m3/drv/ser_lm3s.h b/bertos/cpu/cortex-m3/drv/ser_lm3s.h
new file mode 100644 (file)
index 0000000..27da414
--- /dev/null
@@ -0,0 +1,145 @@
+/**
+ * \file
+ * <!--
+ * This file is part of BeRTOS.
+ *
+ * Bertos is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ * As a special exception, you may use this file as part of a free software
+ * library without restriction.  Specifically, if other files instantiate
+ * templates or use macros or inline functions from this file, or you compile
+ * this file and link it with other files to produce an executable, this
+ * file does not by itself cause the resulting executable to be covered by
+ * the GNU General Public License.  This exception does not however
+ * invalidate any other reasons why the executable file might be covered by
+ * the GNU General Public License.
+ *
+ * Copyright 2010 Develer S.r.l. (http://www.develer.com/)
+ *
+ * -->
+ *
+ * \brief LM3S1968 UART interface driver.
+ *
+ * \author Andrea Righi <arighi@develer.com>
+ */
+
+#ifndef SER_LM3S_H
+#define SER_LM3S_H
+
+#include <cfg/cfg_debug.h>
+#include <cpu/power.h> /* cpu_relax() */
+#include <io/lm3s.h>
+
+/* Serial hardware numbers */
+enum
+{
+       SER_UART0,
+       SER_UART1,
+       SER_UART2,
+
+       SER_CNT //< Number of serial ports
+};
+
+/* Software errors */
+#define SERRF_RXFIFOOVERRUN  BV(0) //< Rx FIFO buffer overrun
+#define SERRF_RXTIMEOUT      BV(1) //< Receive timeout
+#define SERRF_TXTIMEOUT      BV(2) //< Transmit timeout
+
+/*
+ * Hardware errors.
+ */
+#define SERRF_RXSROVERRUN    0 //< Input overrun
+#define SERRF_FRAMEERROR     0 //< Stop bit missing
+#define SERRF_PARITYERROR    0 //< Parity error
+#define SERRF_NOISEERROR     0 //< Noise error
+
+/* Serial error/status flags */
+typedef uint32_t serstatus_t;
+
+INLINE void lm3s_uartDisable(uint32_t base)
+{
+       /* Disable the hardware FIFO */
+       HWREG(base + UART_O_LCRH) &= ~UART_LCRH_FEN;
+
+       /* Disable the UART */
+       HWREG(base + UART_O_CTL) &=
+               ~(UART_CTL_UARTEN | UART_CTL_TXE | UART_CTL_RXE);
+}
+
+INLINE void lm3s_uartEnable(uint32_t base)
+{
+       /* Enable the hardware FIFO */
+       HWREG(base + UART_O_LCRH) |= UART_LCRH_FEN;
+
+       /* Enable RX, TX, and the UART */
+       HWREG(base + UART_O_CTL) |=
+                       UART_CTL_UARTEN | UART_CTL_TXE | UART_CTL_RXE;
+}
+
+INLINE bool lm3s_uartTxDone(uint32_t base)
+{
+       return HWREG(base + UART_O_FR) & UART_FR_TXFE ? true : false;
+}
+
+INLINE bool lm3s_uartTxReady(uint32_t base)
+{
+       return HWREG(base + UART_O_FR) & UART_FR_TXFF ? false : true;
+}
+
+INLINE bool lm3s_uartRxReady(uint32_t base)
+{
+       return HWREG(base + UART_O_FR) & UART_FR_RXFE ? false : true;
+}
+
+INLINE bool lm3s_uartReady(uint32_t base)
+{
+       return HWREG(base + UART_O_FR) & UART_FR_BUSY ? false : true;
+}
+
+INLINE int lm3s_uartPutCharNonBlocking(uint32_t base, unsigned char c)
+{
+       if (!lm3s_uartTxReady(base))
+               return EOF;
+       HWREG(base + UART_O_DR) = c;
+       return c;
+}
+
+INLINE int lm3s_uartPutChar(uint32_t base, unsigned char c)
+{
+       while (!lm3s_uartTxReady(base))
+               cpu_relax();
+       HWREG(base + UART_O_DR) = c;
+       return c;
+}
+
+INLINE int lm3s_uartGetCharNonBlocking(uint32_t base)
+{
+       if (!lm3s_uartRxReady(base))
+               return EOF;
+       return HWREG(base + UART_O_DR);
+}
+
+INLINE int lm3s_uartGetChar(uint32_t base)
+{
+       while (!lm3s_uartRxReady(base))
+               cpu_relax();
+       return HWREG(base + UART_O_DR);
+}
+
+void lm3s_uartSetBaudRate(uint32_t base, unsigned long baud);
+void lm3s_uartSetParity(uint32_t base, int parity);
+void lm3s_uartInit(int port);
+
+#endif /* SER_LM3S_H */