Add serial module.
authorasterix <asterix@38d2e660-2303-0410-9eaa-f027e97ec537>
Wed, 23 Jun 2010 16:54:03 +0000 (16:54 +0000)
committerasterix <asterix@38d2e660-2303-0410-9eaa-f027e97ec537>
Wed, 23 Jun 2010 16:54:03 +0000 (16:54 +0000)
git-svn-id: https://src.develer.com/svnoss/bertos/trunk@3938 38d2e660-2303-0410-9eaa-f027e97ec537

bertos/cpu/cortex-m3/drv/ser_stm32.c [new file with mode: 0644]
bertos/cpu/cortex-m3/drv/ser_stm32.h [new file with mode: 0644]

diff --git a/bertos/cpu/cortex-m3/drv/ser_stm32.c b/bertos/cpu/cortex-m3/drv/ser_stm32.c
new file mode 100644 (file)
index 0000000..315329b
--- /dev/null
@@ -0,0 +1,387 @@
+/**
+ * \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 STM32 UART interface driver.
+ *
+ * \author Daniele Basile <asterix@develer.com>
+ */
+
+#include "ser_stm32.h"
+
+#include "cfg/cfg_ser.h"
+
+#include <cfg/macros.h> /* for BV() */
+#include <cfg/debug.h>
+
+#include <drv/gpio_stm32.h>
+#include <drv/irq_cm3.h>
+#include <drv/clock_stm32.h>
+#include <drv/ser_p.h>
+#include <drv/ser.h>
+
+
+/* From the high-level serial driver */
+extern struct Serial *ser_handles[SER_CNT];
+
+struct CM3Serial
+{
+       struct SerialHardware hw;
+       volatile bool sending;
+       uint32_t base;
+       sysirq_t irq;
+};
+
+/* Forward declaration */
+static struct CM3Serial UARTDesc[SER_CNT];
+
+/* GPIO descriptor for UART pins */
+struct gpio_uart_info
+{
+       /* GPIO base address register */
+       uint32_t base;
+       /* Pin(s) bitmask */
+       uint32_t rx_pin;
+       uint32_t tx_pin;
+       /* Sysctl */
+       uint32_t sysctl;
+       uint32_t sysctl1;
+
+};
+
+/* Table to retrieve GPIO pins configuration to work as UART pins */
+static const struct gpio_uart_info gpio_uart[SER_CNT] =
+{
+       /* UART1 */
+       {
+               .base = GPIOA_BASE,
+               .rx_pin = GPIO_USART1_RX_PIN,
+               .tx_pin = GPIO_USART1_TX_PIN,
+               .sysctl = RCC_APB2_GPIOA,
+               .sysctl1 = RCC_APB2_USART1,
+       },
+       /* UART2 */
+       {
+               .base = GPIOA_BASE,
+               .rx_pin = GPIO_USART2_RX_PIN,
+               .tx_pin = GPIO_USART2_TX_PIN,
+               .sysctl = RCC_APB2_GPIOA,
+               .sysctl1 = RCC_APB1_USART2,
+       },
+       /* UART3 */
+       {
+               .base = GPIOB_BASE,
+               .rx_pin = GPIO_USART3_RX_PIN,
+               .tx_pin = GPIO_USART3_TX_PIN,
+               .sysctl = RCC_APB2_GPIOB,
+               .sysctl1 = RCC_APB1_USART3,
+       },
+};
+
+#define USART1_PORT                0
+#define USART2_PORT                1
+#define USART3_PORT                2
+
+void stm32_uartSetBaudRate(uint32_t base, unsigned long baud)
+{
+       struct stm32_usart *_base = (struct stm32_usart *)base;
+       _base->BRR = evaluate_brr(_base, CPU_FREQ, baud);
+}
+
+void stm32_uartSetParity(uint32_t base, int parity)
+{
+       struct stm32_usart *_base = (struct stm32_usart *)base;
+
+       /*  USART_WORD_LEN_8B */
+       _base->CR1 &= ~BV(CR1_M);
+
+       switch(parity)
+       {
+       case SER_PARITY_NONE:
+               _base->CR1 &= ~BV(CR1_PCE);
+               break;
+       case SER_PARITY_ODD:
+               _base->CR1 |= (BV(CR1_PCE) | BV(CR1_PS));
+               break;
+       case SER_PARITY_EVEN:
+               _base->CR1 |= BV(CR1_PCE);
+               _base->CR1 &= ~BV(CR1_PS);
+               break;
+       default:
+               ASSERT(0);
+               return;
+       }
+}
+
+void stm32_uartInit(int port)
+{
+       struct stm32_usart *base = (struct stm32_usart *)UARTDesc[port].base;
+
+       kprintf("init port[%d]cnt[%d]\n", port, SER_CNT);
+       ASSERT(port >= 0 && port < SER_CNT);
+
+       /* Enable clocking on AFIO */
+       RCC->APB2ENR |= RCC_APB2_AFIO;
+
+       /* Configure USART pins */
+       if (port == USART1_PORT)
+       {
+               RCC->APB2ENR |=  gpio_uart[port].sysctl;
+               RCC->APB2ENR |=  gpio_uart[port].sysctl1;
+       }
+       else
+       {
+               RCC->APB1ENR |=  gpio_uart[port].sysctl;
+               RCC->APB1ENR |=  gpio_uart[port].sysctl1;
+       }
+
+       stm32_gpioPinConfig((struct stm32_gpio *)gpio_uart[port].base,  gpio_uart[port].tx_pin,
+                               GPIO_MODE_AF_PP, GPIO_SPEED_50MHZ);
+
+       stm32_gpioPinConfig((struct stm32_gpio *)gpio_uart[port].base,  gpio_uart[port].rx_pin,
+                               GPIO_MODE_IN_FLOATING, GPIO_SPEED_50MHZ);
+
+       /* Clear control registry */
+       base->CR2 = 0; //CR2_CLEAR_MASK;
+       base->CR1 = 0; //CR1_CLEAR_MASK;
+       base->CR3 = 0; //CR3_CLEAR_MASK;
+       base->SR = 0;
+
+       /* Set serial param: 115.200 bps, no parity */
+       stm32_uartSetBaudRate(UARTDesc[port].base, 115200);
+       stm32_uartSetParity(UARTDesc[port].base, SER_PARITY_NONE);
+
+
+       /* Enable trasmision and receiver */
+       base->CR1 |= (BV(CR1_TE) | BV(CR1_RE));
+
+
+       kprintf("INIT[%02x]\n", (uint8_t)base->SR); \
+
+}
+
+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;
+       struct stm32_usart *base = (struct stm32_usart *)UARTDesc[port].base;
+       char c;
+
+       while (stm32_uartRxReady(UARTDesc[port].base))
+       {
+               c = base->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;
+       struct stm32_usart *base = (struct stm32_usart *)UARTDesc[port].base;
+
+       if (fifo_isempty(txfifo))
+       {
+               /*
+                * Disable TX empty interrupts if there're no more
+                * characters to transmit.
+                */
+               base->CR1 &= ~BV(7);
+               UARTDesc[port].sending = false;
+       }
+       else
+       {
+               base->DR = fifo_pop(txfifo);
+       }
+}
+
+static void uart_common_irq_handler(int port)
+{
+       struct stm32_usart *base = (struct stm32_usart *)UARTDesc[port].base;
+       uint32_t status;
+
+       /* Read and clear the IRQ status */
+       status = base->SR;
+       /* Process the IRQ */
+       if (status & BV(5))
+       {
+               uart_irq_rx(port);
+       }
+       if (status & (BV(7) | BV(6)))
+       {
+               uart_irq_tx(port);
+       }
+}
+
+static void stm32_uartIRQEnable(int port, sysirq_handler_t handler)
+{
+       struct stm32_usart *base = (struct stm32_usart *)UARTDesc[port].base;
+
+       /* Register the IRQ handler */
+       sysirq_setHandler(UARTDesc[port].irq, handler);
+
+       base->CR1 |= BV(5);
+}
+
+static void stm32_uartIRQDisable(int port)
+{
+       struct stm32_usart *base = (struct stm32_usart *)UARTDesc[port].base;
+
+       base->CR1 &= ~(BV(5) | USART_FLAG_TXE);
+}
+
+
+/* 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(USART ## port ## _PORT);        \
+       }                                                                       \
+                                                                               \
+       /* UART public methods */ \
+       static void     uart ## port ## _txStart(struct SerialHardware *_hw) \
+       {                                                                                                                                \
+               struct FIFOBuffer *txfifo = &ser_handles[USART ## port ## _PORT]->txfifo;                \
+               struct CM3Serial *hw = (struct CM3Serial *)_hw;                      \
+               struct stm32_usart *base = (struct stm32_usart *)USART## port ## _BASE; \
+               if (hw->sending)                                                \
+                       return;                                                 \
+               stm32_uartPutChar(USART ## port ## _BASE, fifo_pop(txfifo));    \
+               if (!fifo_isempty(txfifo))                                      \
+               {                                                               \
+                       kputs("tx_en_irq\n"); \
+                       hw->sending = true;      \
+                       base->CR1 |= BV(7); \
+               } \
+       }                                                                       \
+                                                                               \
+       static void     uart ## port ## _setbaudrate(UNUSED_ARG(struct SerialHardware *, hw), \
+                                               unsigned long baud)             \
+       {                                                                       \
+               stm32_uartSetBaudRate(USART## port ## _BASE, baud);             \
+       }                                                                       \
+                                                                               \
+       static void     uart ## port ## _setparity(UNUSED_ARG(struct SerialHardware *, hw),     \
+                                               int parity)                     \
+       {                                                                       \
+               stm32_uartSetParity(USART## port ## _BASE, parity);             \
+       }                                                                       \
+                                                                               \
+       static void     uart ## port ## _cleanup(struct SerialHardware *_hw)                    \
+       {                                                                       \
+               struct CM3Serial *hw = (struct CM3Serial *)_hw;                 \
+               hw->sending = false; \
+               stm32_uartIRQDisable(USART ## port ## _PORT);                                   \
+               stm32_uartClear(USART## port ## _BASE);                         \
+               stm32_uartDisable(USART## port ## _BASE);                       \
+       }                                                                       \
+                                                                               \
+       static void     uart ## port ## _init(UNUSED_ARG(struct SerialHardware *, hw),          \
+                               UNUSED_ARG(struct Serial *, ser))               \
+       {                                                                       \
+               stm32_uartInit(USART ## port ## _PORT);                                         \
+               stm32_uartEnable(USART## port ## _BASE);                                \
+               stm32_uartIRQEnable(USART ## port ## _PORT, uart ## port ## _irq_handler);              \
+       }                                                                       \
+                                                                               \
+       /* UART operations */                                                   \
+       static const struct SerialHardwareVT USART ## 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(1)
+UART_PORT(2)
+UART_PORT(3)
+
+static struct CM3Serial UARTDesc[SER_CNT] =
+{
+       {
+               .hw = {
+                       .table = &USART1_VT,
+                       .txbuffer = uart1_txbuffer,
+                       .rxbuffer = uart1_rxbuffer,
+                       .txbuffer_size = sizeof(uart1_txbuffer),
+                       .rxbuffer_size = sizeof(uart1_rxbuffer),
+               },
+               .sending = false,
+               .base = USART1_BASE,
+               .irq = USART1_IRQHANDLER,
+       },
+       {
+               .hw = {
+                       .table = &USART2_VT,
+                       .txbuffer = uart2_txbuffer,
+                       .rxbuffer = uart2_rxbuffer,
+                       .txbuffer_size = sizeof(uart2_txbuffer),
+                       .rxbuffer_size = sizeof(uart2_rxbuffer),
+               },
+               .sending = false,
+               .base = USART2_BASE,
+               .irq = USART2_IRQHANDLER,
+       },
+       {
+               .hw = {
+                       .table = &USART3_VT,
+                       .txbuffer = uart3_txbuffer,
+                       .rxbuffer = uart3_rxbuffer,
+                       .txbuffer_size = sizeof(uart3_txbuffer),
+                       .rxbuffer_size = sizeof(uart3_rxbuffer),
+               },
+               .sending = false,
+               .base = USART3_BASE,
+               .irq = USART3_IRQHANDLER,
+       },
+};
+
+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_stm32.h b/bertos/cpu/cortex-m3/drv/ser_stm32.h
new file mode 100644 (file)
index 0000000..2da1b09
--- /dev/null
@@ -0,0 +1,129 @@
+/**
+ * \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 STM32F10xx UART interface driver.
+ *
+ * \author Daniele Basile <asterix@develer.com>
+ */
+
+#ifndef SER_STM32_H
+#define SER_STM32_H
+
+#include <cfg/debug.h>
+
+#include <cpu/power.h> /* cpu_relax() */
+
+#include <io/stm32.h>
+
+/* Serial hardware numbers */
+enum
+{
+       SER_UART1 = 0,
+       SER_UART2,
+       SER_UART3,
+
+       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 stm32_uartDisable(uint32_t base)
+{
+       struct stm32_usart *_base = (struct stm32_usart *)base;
+       _base->CR1 &= ~CR1_RUN_RESET;
+}
+
+INLINE void stm32_uartEnable(uint32_t base)
+{
+       struct stm32_usart *_base = (struct stm32_usart *)base;
+       _base->CR1 |= CR1_RUN_SET;
+}
+
+/* Clear the flags register */
+INLINE void stm32_uartClear(uint32_t base)
+{
+       struct stm32_usart *_base = (struct stm32_usart *)base;
+       _base->SR &= ~USART_FLAG_MASK;
+}
+
+INLINE bool stm32_uartTxDone(uint32_t base)
+{
+       struct stm32_usart *_base = (struct stm32_usart *)base;
+       return (_base->SR & USART_FLAG_TC);
+}
+
+INLINE bool stm32_uartTxReady(uint32_t base)
+{
+       struct stm32_usart *_base = (struct stm32_usart *)base;
+       return (_base->SR & (BV(7) | BV(6)));
+}
+
+INLINE bool stm32_uartRxReady(uint32_t base)
+{
+       struct stm32_usart *_base = (struct stm32_usart *)base;
+       return (_base->SR & BV(5));
+}
+
+INLINE int stm32_uartPutChar(uint32_t base, unsigned char c)
+{
+       struct stm32_usart *_base = (struct stm32_usart *)base;
+       while (!stm32_uartTxReady(base))
+               cpu_relax();
+       _base->DR = c;
+       return c;
+}
+
+INLINE int stm32_uartGetChar(uint32_t base)
+{
+       struct stm32_usart * _base = (struct stm32_usart *)base;
+       return _base->DR;
+}
+
+void stm32_uartSetBaudRate(uint32_t base, unsigned long baud);
+void stm32_uartSetParity(uint32_t base, int parity);
+void stm32_uartInit(int port);
+
+#endif /* SER_STM32_H */