From 51f196d5191f0c9a47f2642af5b7b1871c02a0fa Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 31 Oct 2008 22:39:11 +0000 Subject: Add STR71x serial driver git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1110 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/str71x/Make.defs | 6 +- nuttx/arch/arm/src/str71x/str71x_gpio.h | 23 +- nuttx/arch/arm/src/str71x/str71x_head.S | 2 +- nuttx/arch/arm/src/str71x/str71x_lowputc.c | 334 +++++++++ nuttx/arch/arm/src/str71x/str71x_map.h | 63 -- nuttx/arch/arm/src/str71x/str71x_serial.c | 1003 ++++++++++++++++++++++++++++ nuttx/arch/arm/src/str71x/str71x_uart.h | 13 +- 7 files changed, 1367 insertions(+), 77 deletions(-) create mode 100644 nuttx/arch/arm/src/str71x/str71x_lowputc.c create mode 100644 nuttx/arch/arm/src/str71x/str71x_serial.c (limited to 'nuttx') diff --git a/nuttx/arch/arm/src/str71x/Make.defs b/nuttx/arch/arm/src/str71x/Make.defs index a59ea4a2c..c6e0e23c4 100644 --- a/nuttx/arch/arm/src/str71x/Make.defs +++ b/nuttx/arch/arm/src/str71x/Make.defs @@ -47,9 +47,9 @@ ifneq ($(CONFIG_DISABLE_SIGNALS),y) CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c endif -CHIP_ASRCS = str71x_lowputc.S -CHIP_CSRCS = str71x_prccu.c str71x_decodeirq.c str71x_irq.c str71x_timerisr.c \ - str71x_serial.c +CHIP_ASRCS = +CHIP_CSRCS = str71x_prccu.c str71x_lowputc.c str71x_decodeirq.c str71x_irq.c \ + str71x_timerisr.c str71x_serial.c ifeq ($(CONFIG_USBDEV),y) CHIP_CSRCS += str71x_usbdev.c diff --git a/nuttx/arch/arm/src/str71x/str71x_gpio.h b/nuttx/arch/arm/src/str71x/str71x_gpio.h index 99f2e6f35..2eb92939a 100644 --- a/nuttx/arch/arm/src/str71x/str71x_gpio.h +++ b/nuttx/arch/arm/src/str71x/str71x_gpio.h @@ -57,10 +57,25 @@ /* GPIO register addresses **********************************************************/ -#define STR71X_GPIO_PC0 (STR71X_GPIO_BASE + STR71X_GPIO_PC0_OFFSET) -#define STR71X_GPIO_PC1 (STR71X_GPIO_BASE + STR71X_GPIO_PC1_OFFSET) -#define STR71X_GPIO_PC2 (STR71X_GPIO_BASE + STR71X_GPIO_PC2_OFFSET) -#define STR71X_GPIO_PD (STR71X_GPIO_BASE + STR71X_GPIO_PD_OFFSET) +#define STR71X_GPIO_PC0(b) ((b) + STR71X_GPIO_PC0_OFFSET) +#define STR71X_GPIO_PC1(b) ((b) + STR71X_GPIO_PC1_OFFSET) +#define STR71X_GPIO_PC2(b) ((b) + STR71X_GPIO_PC2_OFFSET) +#define STR71X_GPIO_PD(b) ((b) + STR71X_GPIO_PD_OFFSET) + +#define STR71X_GPIO0_PC0 (STR71X_GPIO0_BASE + STR71X_GPIO_PC0_OFFSET) +#define STR71X_GPIO0_PC1 (STR71X_GPIO0_BASE + STR71X_GPIO_PC1_OFFSET) +#define STR71X_GPIO0_PC2 (STR71X_GPIO0_BASE + STR71X_GPIO_PC2_OFFSET) +#define STR71X_GPIO0_PD (STR71X_GPIO0_BASE + STR71X_GPIO_PD_OFFSET) + +#define STR71X_GPIO1_PC0 (STR71X_GPIO1_BASE + STR71X_GPIO_PC0_OFFSET) +#define STR71X_GPIO1_PC1 (STR71X_GPIO1_BASE + STR71X_GPIO_PC1_OFFSET) +#define STR71X_GPIO1_PC2 (STR71X_GPIO1_BASE + STR71X_GPIO_PC2_OFFSET) +#define STR71X_GPIO1_PD (STR71X_GPIO1_BASE + STR71X_GPIO_PD_OFFSET) + +#define STR71X_GPIO2_PC0 (STR71X_GPIO2_BASE + STR71X_GPIO_PC0_OFFSET) +#define STR71X_GPIO2_PC1 (STR71X_GPIO2_BASE + STR71X_GPIO_PC1_OFFSET) +#define STR71X_GPIO2_PC2 (STR71X_GPIO2_BASE + STR71X_GPIO_PC2_OFFSET) +#define STR71X_GPIO2_PD (STR71X_GPIO2_BASE + STR71X_GPIO_PD_OFFSET) /* Register bit settings ************************************************************/ diff --git a/nuttx/arch/arm/src/str71x/str71x_head.S b/nuttx/arch/arm/src/str71x/str71x_head.S index 715b00446..bbb3df34a 100644 --- a/nuttx/arch/arm/src/str71x/str71x_head.S +++ b/nuttx/arch/arm/src/str71x/str71x_head.S @@ -553,7 +553,7 @@ __flashstart: bl str71x_prccuinit /* Configure the uart so that we can get debug output as soon - * as possible. Modifies r0, r1, r2, and r14. + * as possible. */ bl up_lowsetup diff --git a/nuttx/arch/arm/src/str71x/str71x_lowputc.c b/nuttx/arch/arm/src/str71x/str71x_lowputc.c new file mode 100644 index 000000000..02d8d9350 --- /dev/null +++ b/nuttx/arch/arm/src/str71x/str71x_lowputc.c @@ -0,0 +1,334 @@ +/************************************************************************** + * arch/arm/src/str71x/str71x_lowputc.c + * + * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + **************************************************************************/ + +/************************************************************************** + * Included Files + **************************************************************************/ + +#include +#include "up_internal.h" +#include "up_arch.h" +#include "chp.h" + +/************************************************************************** + * Private Definitions + **************************************************************************/ + +/* Configuration **********************************************************/ + +/* Is there a UART enabled? */ + +#if defined(CONFIG_STR71X_UART0) || defined(CONFIG_STR71X_UART1) || \ + defined(CONFIG_STR71X_UART2) || defined(CONFIG_STR71X_UART3)) +# define HAVE_UART 1 + +/* Is there a serial console? */ + +# if defined(CONFIG_UART0_SERIAL_CONSOLE) || defined(CONFIG_UART1_SERIAL_CONSOLE) ||\ + defined(CONFIG_UART2_SERIAL_CONSOLE) || defined(CONFIG_UART3_SERIAL_CONSOLE) +# define HAVE_CONSOLE +# else +# undef HAVE_CONSOLE +# endif + +#else +# undef HAVE_UART +# undef HAVE_CONSOLE +#endif + +/* GPIO0 UART configuration bits */ + +#if CONFIG_STR71X_UART0 +# define STR71X_UART0_GPIO0_MASK (0x0300) /* P0.8->U0.TX, B0.9->U0.RX */ +# define STR71X_UART0_GPIO0_PC0BITS (0x0300) +# define STR71X_UART0_GPIO0_PC1BITS (0x0200) +# define STR71X_UART0_GPIO0_PC2BITS (0x0200) +#else +# define STR71X_UART0_GPIO0_MASK (0) +# define STR71X_UART0_GPIO0_PC0BITS (0) +# define STR71X_UART0_GPIO0_PC1BITS (0) +# define STR71X_UART0_GPIO0_PC2BITS (0) +#endif + +#if CONFIG_STR71X_UART0 +# define STR71X_UART1_GPIO0_MASK (0x0c00) /* P0,10->U1.RX, P0.11->U1.TX */ +# define STR71X_UART1_GPIO0_PC0BITS (0x0c00) +# define STR71X_UART1_GPIO0_PC1BITS (0x0800) +# define STR71X_UART1_GPIO0_PC2BITS (0x0800) +#else +# define STR71X_UART1_GPIO0_MASK (0) +# define STR71X_UART1_GPIO0_PC0BITS (0) +# define STR71X_UART1_GPIO0_PC1BITS (0) +# define STR71X_UART1_GPIO0_PC2BITS (0) +#endif + +#if CONFIG_STR71X_UART0 +# define STR71X_UART2_GPIO0_MASK (0x6000) /* P0.13->U2.RX, P0.14>U2.TX */ +# define STR71X_UART2_GPIO0_PC0BITS (0x6000) +# define STR71X_UART2_GPIO0_PC1BITS (0x4000) +# define STR71X_UART2_GPIO0_PC2BITS (0x4000) +#else +# define STR71X_UART2_GPIO0_MASK (0) +# define STR71X_UART2_GPIO0_PC0BITS (0) +# define STR71X_UART2_GPIO0_PC1BITS (0) +# define STR71X_UART2_GPIO0_PC2BITS (0) +#endif + +#if CONFIG_STR71X_UART0 +# define STR71X_UART3_GPIO0_MASK (0x0003) /* P0.0->U3.TX, P0.1->U3.RX */ +# define STR71X_UART3_GPIO0_PC0BITS (0x0003) +# define STR71X_UART3_GPIO0_PC1BITS (0x0001) +# define STR71X_UART3_GPIO0_PC2BITS (0x0001) +#else +# define STR71X_UART3_GPIO0_MASK (0) +# define STR71X_UART3_GPIO0_PC0BITS (0) +# define STR71X_UART3_GPIO0_PC1BITS (0) +# define STR71X_UART3_GPIO0_PC2BITS (0) +#endif + +#define STR71X_UART_GPIO0_MASK (STR71X_UART0_GPIO0_MASK |STR71X_UART1_GPIO0_MASK|\ + STR71X_UART2_GPIO0_MASK |STR71X_UART3_GPIO0_MASK) +#define STR71X_UART_GPIO0_PC0BITS (STR71X_UART0_GPIO0_PC0BITS|STR71X_UART1_GPIO0_PC0BITS|\ + STR71X_UART2_GPIO0_PC0BITS|STR71X_UART3_GPIO0_PC0BITS) +#define STR71X_UART_GPIO0_PC1BITS (STR71X_UART0_GPIO0_PC0BITS|STR71X_UART1_GPIO0_PC0BITS|\ + STR71X_UART2_GPIO0_PC0BITS|STR71X_UART3_GPIO0_PC0BITS) +#define STR71X_UART_GPIO0_PC2BITS (STR71X_UART0_GPIO0_PC0BITS|STR71X_UART1_GPIO0_PC0BITS|\ + STR71X_UART2_GPIO0_PC0BITS|STR71X_UART3_GPIO0_PC0BITS) + +/* Select UART parameters for the selected console */ + +#if defined(CONFIG_UART0_SERIAL_CONSOLE) +# define STR71X_UART_BASE STR71X_UART0_BASE +# define STR71X_UART_BAUD CONFIG_UART0_BAUD +# define STR71X_UART_BITS CONFIG_UART0_BITS +# define STR71X_UART_PARITY CONFIG_UART0_PARITY +# define STR71X_UART_2STOP CONFIG_UART0_2STOP +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) +# define STR71X_UART_BASE STR71X_UART1_BASE +# define STR71X_UART_BAUD CONFIG_UART1_BAUD +# define STR71X_UART_BITS CONFIG_UART1_BITS +# define STR71X_UART_PARITY CONFIG_UART1_PARITY +# define STR71X_UART_2STOP CONFIG_UART1_2STOP +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) +# define STR71X_UART_BASE STR71X_UART2_BASE +# define STR71X_UART_BAUD CONFIG_UART2_BAUD +# define STR71X_UART_BITS CONFIG_UART2_BITS +# define STR71X_UART_PARITY CONFIG_UART2_PARITY +# define STR71X_UART_2STOP CONFIG_UART2_2STOP +#elif defined(CONFIG_UART3_SERIAL_CONSOLE) +# define STR71X_UART_BASE STR71X_UART3_BASE +# define STR71X_UART_BAUD CONFIG_UART3_BAUD +# define STR71X_UART_BITS CONFIG_UART3_BITS +# define STR71X_UART_PARITY CONFIG_UART3_PARITY +# define STR71X_UART_2STOP CONFIG_UART3_2STOP +#else +# error "No CONFIG_UARTn_SERIAL_CONSOLE Setting" +#endif + +/* Get mode setting */ + +#if STR71X_UART_BITS == 7 +# if STR71X_UART_PARITY == 0 +# error "7-bits, no parity mode not supported" +# else +# define STR71X_UARTCR_MODE STR71X_UARTCR_MODE7BITP +# endif +#elif STR71X_UART_BITS == 8 +# if STR71X_UART_PARITY == 0 +# define STR71X_UARTCR_MODE STR71X_UARTCR_MODE8BIT +# else +# define STR71X_UARTCR_MODE STR71X_UARTCR_MODE8BITP +# endif +#elif STR71X_UART_BITS == 9 +# if STR71X_UART_PARITY == 0 +# define STR71X_UARTCR_MODE STR71X_UARTCR_MODE9BIT +# else +# error "9-bits with parity not supported" +# endif +#else +# error "Number of bits not supported" +#endif + +#if STR71X_UART_PARITY == 0 || STR71X_UART_PARITY == 2 +# define STR71X_UARTCR_PARITY (0) +#elif STR71X_UART_PARITY == 1 +# define STR71X_UARTCR_PARITY STR71X_UARTCR_PARITYODD +#else +# error "Invalid parity selection" +#endif + +#if STR71X_UART_2STOP != 0 +# define STR71X_UARTCR_STOP STR71X_UARTCR_STOPBIT20 +#else +# define STR71X_UARTCR_STOP STR71X_UARTCR_STOPBIT05 +#endif + +#define STR71X_UARTCR_VALUE (STR71X_UARTCR_MODE|STR71X_UARTCR_PARITY|STR71X_UARTCR_STOP|\ + STR71X_UARTCR_RUN|STR71X_UARTCR_RXENABLE|STR71X_UARTCR_FIFOENABLE) + +/* Calculate the value of PCLK1 from settings in board.h. + * + * Example: + * STR71X_RCCU_MAIN_OSC = 4MHz (not divided by 2) + * CLK2 = 4MHz + * PLL1OUT = 16 * CLK2 / 2 = 32MHz + * CLK3 = 32MHz + * RCLK = 32MHz + * PCLK1 = 32MHz / 1 = 32MHz + */ + +#ifdef STR71X_PLL1IN_DIV2 /* Input may be divided by 2 */ +# define CLK2 (STR71X_RCCU_MAIN_OSC/2) /* CLK2 is input to PLL1 */ +#else +# define CLK2 STR71X_RCCU_MAIN_OSC /* CLK2 is input to PLL1 */ +#endif + /* PLL1OUT derives from CLK2 */ +#define PLL1OUT (STR71X_PLL1OUT_MUL * CLK2 / STR71X_PLL1OUT_DIV) +#define CLK3 PLL1OUT /* CLK3 hard coded to be PLL1OUT */ +#define RCLK CLK3 /* RCLK hard coded to be CLK3 */ +#define PCLK1 (RCLK / STR71X_APB1_DIV) /* PCLK1 derives from RCLK */ + +/* Calculate BAUD rate from PCLK1: + * + * Example: + * PCLK1 = 32MHz + * STR71X_UART_BAUD = 38,400 + * UART_BAUDRATE_DIVISOR = 614,400 + * UART_BAUDRATE = 52.583 (exact) or 52 truncated (1.1% error) + */ + +#define UART_BAUDDIVISOR (16 * STR71X_UART_BAUD) +#define UART_BAUDRATE ((PCLK1 + (UART_BAUDDIVISOR/2) / UART_BAUDDIVISOR) + +/************************************************************************** + * Private Types + **************************************************************************/ + +/************************************************************************** + * Private Function Prototypes + **************************************************************************/ + +/************************************************************************** + * Global Variables + **************************************************************************/ + +/************************************************************************** + * Private Variables + **************************************************************************/ + +/************************************************************************** + * Private Functions + **************************************************************************/ + +/************************************************************************** + * Public Functions + **************************************************************************/ + +/************************************************************************** + * Name: up_lowputc + * + * Description: + * Output one byte on the serial console + * + **************************************************************************/ + +void up_lowputc(char ch) +{ +#if HAVE_CONSOLE + uint16 reg16; + + /* Wait until the TX FIFO is not full */ + + while (getreg16(STR71X_UART_SR(STR71X_UART_BASE)) & STR71X_UARTSR_TF != 0); + + /* Then send the character */ + + putreg16((uint16)ch, STR71X_UART_TXBUFR(STR71X_UART_BASE)); +#endif +} + +/************************************************************************** + * Name: up_lowsetup + * + * Description: + * This performs basic initialization of the UART used for the serial + * console. Its purpose is to get the console output availabe as soon + * as possible. + * + **************************************************************************/ + +void up_lowsetup(void) +{ +#if HAVE_CONSOLE + uint16 reg16; + + /* Enable the selected console device */ + /* Set the UART baud rate */ + + putreg16(UART_BAUDRATE, STR71X_UART_BR(STR71X_UART_BASE)); + + /* Configure the UART control registers */ + + putreg16(STR71X_UARTCR_VALUE, STR71X_UART_CR(STR71X_UART_BASE)); + + /* Clear FIFOs */ + + putreg16(0, STR71X_UART2_TXRSTR_(STR71X_UART_BASE)); + putreg16(0, SSTR71X_UART2_RXRSTR(STR71X_UART_BASE)); +#endif + + /* Configure GPIO0 pins to enable all UARTs in the configuration + * (the serial driver later depends on this configuration) + */ + +#if HAVE_UART + reg16 = getreg16(STR71X_GPIO_PC0_OFFSET); + reg16 &= STR71X_GPIO0_MASK; + reg16 |= STR71X_GPIO0_PC0BITS; + putreg16(reg16, STR71X_GPIO_PC0_OFFSET); + + reg16 = getreg16(STR71X_GPIO_PC1_OFFSET); + reg16 &= STR71X_GPIO0_MASK; + reg16 |= STR71X_GPIO0_PC1BITS; + putreg16(reg16, STR71X_GPIO_PC1_OFFSET); + + reg16 = getreg16(STR71X_GPIO_PC2_OFFSET); + reg16 &= STR71X_GPIO0_MASK; + reg16 |= STR71X_GPIO0_PC2BITS; + putreg16(reg16, STR71X_GPIO_PC2_OFFSET); +#endif +} + + diff --git a/nuttx/arch/arm/src/str71x/str71x_map.h b/nuttx/arch/arm/src/str71x/str71x_map.h index 254ac7905..419215297 100644 --- a/nuttx/arch/arm/src/str71x/str71x_map.h +++ b/nuttx/arch/arm/src/str71x/str71x_map.h @@ -98,66 +98,3 @@ ************************************************************************************/ #endif // __ARCH_ARM_SRC_STR71X_STR71X_MAP_H - - -/*------------------------ Analog to Digital Converter -----------------------*/ - -/*------------------------ APB -----------------------------------------------*/ - -/*------------------------ Buffered Serial Peripheral Interface --------------*/ - -/*------------------------ Controller Area Network ---------------------------*/ - -/*------------------------ Enhanced Interrupt Controller ---------------------*/ -/*------------------------ External Memory Interface -------------------------*/ - -/*------------------------ General Purpose IO ports --------------------------*/ - -/*------------------------ I2C interface -------------------------------------*/ - -/*------------------------ Power Reset Clock Control unit --------------------*/ - - -/*------------------------ Real Time Clock -----------------------------------*/ - -/*------------------------ TIM -----------------------------------------------*/ - -/*------------------------ Universal Asynchronous Receiver Transmitter -------*/ - - -/*------------------------ WATCHDOG ------------------------------------------*/ -/*------------------------ External Interrupt Controller ---------------------*/ - - -/* IRQ vectors */ -typedef struct -{ - volatile uint32 T0TIMI_IRQHandler; - volatile uint32 RCCU_IRQHandler; - volatile uint32 RTC_IRQHandler; - volatile uint32 WDG_IRQHandler; - volatile uint32 XTI_IRQHandler; - volatile uint32 USBHP_IRQHandler; - volatile uint32 I2C0ITERR_IRQHandler; - volatile uint32 I2C1ITERR_IRQHandler; - volatile uint32 UART0_IRQHandler; - volatile uint32 UART1_IRQHandler; - volatile uint32 UART2_IRQHandler; - volatile uint32 UART3_IRQHandler; - volatile uint32 BSPI0_IRQHandler; - volatile uint32 BSPI1_IRQHandler; - volatile uint32 I2C0_IRQHandler; - volatile uint32 I2C1_IRQHandler; - volatile uint32 CAN_IRQHandler; - volatile uint32 ADC12_IRQHandler; - volatile uint32 T1TIMI_IRQHandler; - volatile uint32 T2TIMI_IRQHandler; - volatile uint32 T3TIMI_IRQHandler; - uint32 EMPTY1[3]; - volatile uint32 HDLC_IRQHandler; - volatile uint32 USBLP_IRQHandler; - uint32 EMPTY2[2]; - volatile uint32 T0TOI_IRQHandler; - volatile uint32 T0OC1_IRQHandler; - volatile uint32 T0OC2_IRQHandler; -} IRQVectors_TypeDef; diff --git a/nuttx/arch/arm/src/str71x/str71x_serial.c b/nuttx/arch/arm/src/str71x/str71x_serial.c new file mode 100644 index 000000000..8ded616ee --- /dev/null +++ b/nuttx/arch/arm/src/str71x/str71x_serial.c @@ -0,0 +1,1003 @@ +/**************************************************************************** + * arch/arm/src/str71x/str71x_serial.c + * + * Copyright (C) 2008 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" + +#ifdef CONFIG_USE_SERIALDRIVER + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Some sanity checks *******************************************************/ + +/* Is there a UART enabled? */ + +#if !defined(CONFIG_STR71X_UART0) && !defined(CONFIG_STR71X_UART1) && \ + !defined(CONFIG_STR71X_UART2) && !defined(CONFIG_STR71X_UART3)) +# error "No UARTs enabled" +#endif + +/* Is there a serial console? */ + +#if defined(CONFIG_UART0_SERIAL_CONSOLE) || defined(CONFIG_UART1_SERIAL_CONSOLE) ||\ + defined(CONFIG_UART2_SERIAL_CONSOLE) || defined(CONFIG_UART3_SERIAL_CONSOLE) +# define HAVE_CONSOLE +#else +# undef HAVE_CONSOLE +#endif + +/* Which UART with be tty0/console and which tty1? tty2? tty3? */ + +#if defined(CONFIG_UART0_SERIAL_CONSOLE) || !defined(HAVE_CONSOLE) +# ifdef HAVE_CONSOLE +# ifndef CONFIG_STR71X_UART0 +# error "UART0 not selected, cannot be console" +# endif +# define CONSOLE_DEV g_uart0port /* UART0 is console */ +# endif +# define TTYS0_DEV g_uart0port /* UART0 is tty0 */ +# if CONFIG_STR71X_UART1 +# define TTYS1_DEV g_uart1port /* UART1 is tty1 */ +# if CONFIG_STR71X_UART2 +# define TTYS2_DEV g_uart2port /* UART2 is tty2 */ +# if CONFIG_STR71X_UART3 +# define TTYS3_DEV g_uart3port /* UART3 is tty3 */ +# endif +# elif CONFIG_STR71X_UART3 +# define TTYS2_DEV g_uart3port /* UART3 is tty2 */ +# endif +# elif CONFIG_STR71X_UART2 +# define TTYS1_DEV g_uart2port /* UART2 is tty1 */ +# if CONFIG_STR71X_UART3 +# define TTYS2_DEV g_uart3port /* UART3 is tty2 */ +# endif +# elif CONFIG_STR71X_UART3 +# define TTYS1_DEV g_uart3port /* UART3 is tty1 */ +# endif +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) +# ifndef CONFIG_STR71X_UART1 +# error "UART1 not selected, cannot be console" +# endif +# define CONSOLE_DEV g_uart1port /* UART1 is console */ +# define TTYS0_DEV g_uart1port /* UART1 is tty0 */ +# if CONFIG_STR71X_UART0 +# define TTYS1_DEV g_uart0port /* UART0 is tty1 */ +# if CONFIG_STR71X_UART2 +# define TTYS2_DEV g_uart2port /* UART2 is tty2 */ +# if CONFIG_STR71X_UART3 +# define TTYS3_DEV g_uart3port /* UART3 is tty3 */ +# endif +# elif CONFIG_STR71X_UART3 +# define TTYS2_DEV g_uart3port /* UART3 is tty2 */ +# endif +# elif CONFIG_STR71X_UART2 +# define TTYS1_DEV g_uart2port /* UART2 is tty1 */ +# if CONFIG_STR71X_UART3 +# define TTYS2_DEV g_uart3port /* UART3 is tty2 */ +# endif +# elif CONFIG_STR71X_UART3 +# define TTYS1_DEV g_uart3port /* UART3 is tty1 */ +# endif +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) +# ifndef CONFIG_STR71X_UART2 +# error "UART2 not selected, cannot be console" +# endif +# define CONSOLE_DEV g_uart2port /* UART2 is console */ +# define TTYS0_DEV g_uart2port /* UART2 is tty0 */ +# if CONFIG_STR71X_UART0 +# define TTYS1_DEV g_uart0port /* UART0 is tty1 */ +# if CONFIG_STR71X_UART1 +# define TTYS2_DEV g_uart1port /* UART1 is tty2 */ +# if CONFIG_STR71X_UART3 +# define TTYS3_DEV g_uart3port /* UART3 is tty3 */ +# endif +# elif CONFIG_STR71X_UART3 +# define TTYS2_DEV g_uart3port /* UART3 is tty2 */ +# endif +# elif CONFIG_STR71X_UART1 +# define TTYS1_DEV g_uart1port /* UART1 is tty1 */ +# if CONFIG_STR71X_UART3 +# define TTYS2_DEV g_uart3port /* UART3 is tty2 */ +# endif +# elif CONFIG_STR71X_UART3 +# define TTYS1_DEV g_uart3port /* UART3 is tty1 */ +# endif +#elif defined(CONFIG_UART2_SERIAL_CONSOLE) +# ifndef CONFIG_STR71X_UART3 +# error "UART3 not selected, cannot be console" +# endif +# define CONSOLE_DEV g_uart3port /* UART3 is console */ +# define TTYS0_DEV g_uart3port /* UART3 is tty0 */ +# if CONFIG_STR71X_UART0 +# define TTYS1_DEV g_uart0port /* UART0 is tty1 */ +# if CONFIG_STR71X_UART1 +# define TTYS2_DEV g_uart1port /* UART1 is tty2 */ +# if CONFIG_STR71X_UART2 +# define TTYS3_DEV g_uart2port /* UART2 is tty3 */ +# endif +# elif CONFIG_STR71X_UART2 +# define TTYS2_DEV g_uart2port /* UART2 is tty2 */ +# endif +# elif CONFIG_STR71X_UART1 +# define TTYS1_DEV g_uart1port /* UART1 is tty1 */ +# if CONFIG_STR71X_UART2 +# define TTYS2_DEV g_uart2port /* UART2 is tty2 */ +# endif +# elif CONFIG_STR71X_UART2 +# define TTYS1_DEV g_uart2port /* UART2 is tty1 */ +# endif +#else +# warning "No CONFIG_UARTn_SERIAL_CONSOLE Setting" +#endif + +/* Calculate the value of PCLK1 from settings in board.h. + * + * Example: + * STR71X_RCCU_MAIN_OSC = 4MHz (not divided by 2) + * CLK2 = 4MHz + * PLL1OUT = 16 * CLK2 / 2 = 32MHz + * CLK3 = 32MHz + * RCLK = 32MHz + * PCLK1 = 32MHz / 1 = 32MHz + */ + +#ifdef STR71X_PLL1IN_DIV2 /* Input may be divided by 2 */ +# define CLK2 (STR71X_RCCU_MAIN_OSC/2) /* CLK2 is input to PLL1 */ +#else +# define CLK2 STR71X_RCCU_MAIN_OSC /* CLK2 is input to PLL1 */ +#endif + /* PLL1OUT derives from CLK2 */ +#define PLL1OUT (STR71X_PLL1OUT_MUL * CLK2 / STR71X_PLL1OUT_DIV) +#define CLK3 PLL1OUT /* CLK3 hard coded to be PLL1OUT */ +#define RCLK CLK3 /* RCLK hard coded to be CLK3 */ +#define PCLK1 (RCLK / STR71X_APB1_DIV) /* PCLK1 derives from RCLK */ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct up_dev_s +{ + uint32 uartbase; /* Base address of UART registers */ + uint32 baud; /* Configured baud */ + uint16 ier; /* Saved IER value */ + uint16 sr; /* Saved SR value (only used during interrupt processing) */ + ubyte irq; /* IRQ associated with this UART */ + ubyte parity; /* 0=none, 1=odd, 2=even */ + ubyte bits; /* Number of bits (7 or 8) */ + boolean stopbits2; /* TRUE: Configure with 2 stop bits instead of 1 */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int up_setup(struct uart_dev_s *dev); +static void up_shutdown(struct uart_dev_s *dev); +static int up_attach(struct uart_dev_s *dev); +static void up_detach(struct uart_dev_s *dev); +static int up_interrupt(int irq, void *context); +static int up_ioctl(struct file *filep, int cmd, unsigned long arg); +static int up_receive(struct uart_dev_s *dev, uint32 *status); +static void up_rxint(struct uart_dev_s *dev, boolean enable); +static boolean up_rxavailable(struct uart_dev_s *dev); +static void up_send(struct uart_dev_s *dev, int ch); +static void up_txint(struct uart_dev_s *dev, boolean enable); +static boolean up_txready(struct uart_dev_s *dev); +static boolean up_txempty(struct uart_dev_s *dev); + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +struct uart_ops_s g_uart_ops = +{ + .setup = up_setup, + .shutdown = up_shutdown, + .attach = up_attach, + .detach = up_detach, + .ioctl = up_ioctl, + .receive = up_receive, + .rxint = up_rxint, + .rxavailable = up_rxavailable, + .send = up_send, + .txint = up_txint, + .txready = up_txready, + .txempty = up_txempty, +}; + +/* I/O buffers */ + +#ifdef CONFIG_STR71X_UART0 +static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE]; +static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE]; +#endif +#ifdef CONFIG_STR71X_UART1 +static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE]; +static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE]; +#endif +#ifdef CONFIG_STR71X_UART2 +static char g_uart2rxbuffer[CONFIG_UART1_RXBUFSIZE]; +static char g_uart2txbuffer[CONFIG_UART1_TXBUFSIZE]; +#endif +#ifdef CONFIG_STR71X_UART3 +static char g_uart3rxbuffer[CONFIG_UART1_RXBUFSIZE]; +static char g_uart3txbuffer[CONFIG_UART1_TXBUFSIZE]; +#endif + +/* This describes the state of the STR71X uart0 port. */ + +#ifdef CONFIG_STR71X_UART0 +static struct up_dev_s g_uart0priv = +{ + .uartbase = STR71X_UART0_BASE, + .baud = CONFIG_UART0_BAUD, + .irq = STR71X_IRQ_UART0, + .parity = CONFIG_UART0_PARITY, + .bits = CONFIG_UART0_BITS, + .stopbits2 = CONFIG_UART0_2STOP, +}; + +static uart_dev_t g_uart0port = +{ + .recv = + { + .size = CONFIG_UART0_RXBUFSIZE, + .buffer = g_uart0rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART0_TXBUFSIZE, + .buffer = g_uart0txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart0priv, +}; +#endif + +/* This describes the state of the STR71X uart1 port. */ + +#ifdef CONFIG_STR71X_UART1 +static struct up_dev_s g_uart1priv = +{ + .uartbase = STR71X_UART1_BASE, + .baud = CONFIG_UART1_BAUD, + .irq = STR71X_IRQ_UART1, + .parity = CONFIG_UART1_PARITY, + .bits = CONFIG_UART1_BITS, + .stopbits2 = CONFIG_UART1_2STOP, +}; + +static uart_dev_t g_uart1port = +{ + .recv = + { + .size = CONFIG_UART1_RXBUFSIZE, + .buffer = g_uart1rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART1_TXBUFSIZE, + .buffer = g_uart1txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart1priv, +}; +#endif + +/* This describes the state of the STR71X uart2 port. */ + +#ifdef CONFIG_STR71X_UART2 +static struct up_dev_s g_uart2priv = +{ + .uartbase = STR71X_UART2_BASE, + .baud = CONFIG_UART2_BAUD, + .irq = STR71X_IRQ_UART2, + .parity = CONFIG_UART2_PARITY, + .bits = CONFIG_UART2_BITS, + .stopbits2 = CONFIG_UART2_2STOP, +}; + +static uart_dev_t g_uart2port = +{ + .recv = + { + .size = CONFIG_UART2_RXBUFSIZE, + .buffer = g_uart2rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART2_TXBUFSIZE, + .buffer = g_uart2txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart2priv, +}; +#endif + +/* This describes the state of the STR71X uart3 port. */ + +#ifdef CONFIG_STR71X_UART3 +static struct up_dev_s g_uart3priv = +{ + .uartbase = STR71X_UART3_BASE, + .baud = CONFIG_UART3_BAUD, + .irq = STR71X_IRQ_UART3, + .parity = CONFIG_UART3_PARITY, + .bits = CONFIG_UART3_BITS, + .stopbits2 = CONFIG_UART3_2STOP, +}; + +static uart_dev_t g_uart3port = +{ + .recv = + { + .size = CONFIG_UART3_RXBUFSIZE, + .buffer = g_uart3rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART3_TXBUFSIZE, + .buffer = g_uart3txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uart3priv, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_serialin + ****************************************************************************/ + +static inline uint16 up_serialin(struct up_dev_s *priv, int offset) +{ + return getreg16(priv->uartbase + offset); +} + +/**************************************************************************** + * Name: up_serialout + ****************************************************************************/ + +static inline void up_serialout(struct up_dev_s *priv, int offset, uint16 value) +{ + putreg16(value, priv->uartbase + offset); +} + +/**************************************************************************** + * Name: up_disableuartint + ****************************************************************************/ + +static inline void up_disableuartint(struct up_dev_s *priv, uint16 *ier) +{ + if (ier) + { + *ier = priv->ier; + } + + priv->ier =0; + up_serialout(priv, STR71X_UART_IER_OFFSET, 0); +} + +/**************************************************************************** + * Name: up_restoreuartint + ****************************************************************************/ + +static inline void up_restoreuartint(struct up_dev_s *priv, uint16 ier) +{ + priv->ier = ier; + up_serialout(priv, STR71X_UART_IER_OFFSET, ier); +} + +/**************************************************************************** + * Name: up_waittxnotfull + ****************************************************************************/ + +static inline void up_waittxnotfull(struct up_dev_s *priv) +{ + int tmp; + + /* Limit how long we will wait for the TX available condition */ + + for (tmp = 1000 ; tmp > 0 ; tmp--) + { + /* Check TX FIFO is full */ + + if ((up_serialin(priv, STR71X_UART_SR_OFFSET) & STR71X_UARTSR_TF) == 0) + { + /* The TX FIFO is not full... return */ + break; + } + } +} + +/**************************************************************************** + * Name: up_setup + * + * Description: + * Configure the UART baud, bits, parity, fifos, etc. This + * method is called the first time that the serial port is + * opened. + * + ****************************************************************************/ + +static int up_setup(struct uart_dev_s *dev) +{ +#ifndef CONFIG_SUPPRESS_STR71X_UART_CONFIG + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + uint32 divisor; + uint32 baud; + uint16 cr; + + /* Set the BAUD rate */ + + divisor = 16 * priv->baud; + baud = (PCLK1 + divisor/2) / divisor; + up_serialout(priv, STR71X_UART_BR_OFFSET, baud); + + /* Get mode setting */ + + cr = STR71X_UARTCR_RUN|STR71X_UARTCR_RXENABLE|STR71X_UARTCR_FIFOENABLE; + + if (priv->bits == 7) + { + DEBUGASSERT(priv->parity != 0); + cr |= STR71X_UARTCR_MODE7BITP; + } + else if (priv->bits == 8) + { + if (priv->parity) + { + cr |= STR71X_UARTCR_MODE8BITP; + } + else + { + cr |= STR71X_UARTCR_MODE8BIT; + } + } + else + { + DEBUGASSERT(priv->bits == 9 && priv->parity == 0); + cr |= STR71X_UARTCR_MODE9BIT; + } + + if (parity == 1) + { + cr |= STR71X_UARTCR_PARITYODD; + } + + if (priv->stopbits2) + { + cr |= STR71X_UARTCR_STOPBIT20; + } + else + { + cr |= STR71X_UARTCR_STOPBIT05; + } + + putreg16(cr, STR71X_UART_CR_OFFSET); + + /* Clear FIFOs */ + + putreg16(0, STR71X_UART2_TXRSTR_OFFSET); + putreg16(0, SSTR71X_UART2_RXRSTR_OFFSET); + + /* We will take RX interrupts on either the FIFO half full or upon + * a timeout. The timeout is based upon BAUD rate ticks + */ + + putreg16(50, STR71X_UART_TOR_OFFSET); + + /* Set up the IER */ + + priv->ier = up_serialin(priv, STR71X_UART_IER_OFFSET); +#endif + return OK; +} + +/**************************************************************************** + * Name: up_shutdown + * + * Description: + * Disable the UART. This method is called when the serial + * port is closed + * + ****************************************************************************/ + +static void up_shutdown(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + up_disableuartint(priv, NULL); +} + +/**************************************************************************** + * Name: up_attach + * + * Description: + * Configure the UART to operation in interrupt driven mode. This method is + * called when the serial port is opened. Normally, this is just after the + * the setup() method is called, however, the serial console may operate in + * a non-interrupt driven mode during the boot phase. + * + * RX and TX interrupts are not enabled when by the attach method (unless the + * hardware supports multiple levels of interrupt enabling). The RX and TX + * interrupts are not enabled until the txint() and rxint() methods are called. + * + ****************************************************************************/ + +static int up_attach(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + int ret; + + /* Attach and enable the IRQ */ + + ret = irq_attach(priv->irq, up_interrupt); + if (ret == OK) + { + /* Enable the interrupt (RX and TX interrupts are still disabled + * in the UART + */ + + up_enable_irq(priv->irq); + } + return ret; +} + +/**************************************************************************** + * Name: up_detach + * + * Description: + * Detach UART interrupts. This method is called when the serial port is + * closed normally just before the shutdown method is called. The exception is + * the serial console which is never shutdown. + * + ****************************************************************************/ + +static void up_detach(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + up_disable_irq(priv->irq); + irq_detach(priv->irq); +} + +/**************************************************************************** + * Name: up_interrupt + * + * Description: + * This is the UART interrupt handler. It will be invoked + * when an interrupt received on the 'irq' It should call + * uart_transmitchars or uart_receivechar to perform the + * appropriate data transfers. The interrupt handling logic\ + * must be able to map the 'irq' number into the approprite + * uart_dev_s structure in order to call these functions. + * + ****************************************************************************/ + +static int up_interrupt(int irq, void *context) +{ + struct uart_dev_s *dev = NULL; + struct up_dev_s *priv; + int passes; + boolean handled; + +#ifdef CONFIG_STR71X_UART0 + if (g_uart0priv.irq == irq) + { + dev = &g_uart0port; + } + else +#endif +#ifdef CONFIG_STR71X_UART1 + if (g_uart1priv.irq == irq) + { + dev = &g_uart1port; + } + else +#endif +#ifdef CONFIG_STR71X_UART2 + if (g_uart2priv.irq == irq) + { + dev = &g_uart2port; + } + else +#endif +#ifdef CONFIG_STR71X_UART3 + if (g_uart3priv.irq == irq) + { + dev = &g_uart3port; + } + else +#endif + { + PANIC(OSERR_INTERNAL); + } + priv = (struct up_dev_s*)dev->priv; + + /* Loop until there are no characters to be transferred or, + * until we have been looping for a long time. + */ + + for (passes = 0; passes < 256 && handled; passes++) + { + handled = FALSE; + + /* Get the current UART status */ + + priv->sr = up_serialin(priv, STR71X_UART_SR_OFFSET); + + /* Handle incoming, receive bytes (with or without timeout) */ + + if ((priv->sr & STR71X_UARTSR_RNE) != 0) + { + /* Rx buffer not empty ... process incoming bytes */ + + uart_recvchars(dev); + } + + /* Handle outgoing, transmit bytes */ + + if ((priv->sr & STR71X_UARTSR_TF) == 0) + { + /* Tx FIFO not full ... process outgoing bytes */ + + uart_xmitchars(dev); + } + } + return OK; +} + +/**************************************************************************** + * Name: up_ioctl + * + * Description: + * All ioctl calls will be routed through this method + * + ****************************************************************************/ + +static int up_ioctl(struct file *filep, int cmd, unsigned long arg) +{ + struct inode *inode = filep->f_inode; + struct uart_dev_s *dev = inode->i_private; + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + int ret = OK; + + switch (cmd) + { + case TIOCSERGSTRUCT: + { + struct up_dev_s *user = (struct up_dev_s*)arg; + if (!user) + { + *get_errno_ptr() = EINVAL; + ret = ERROR; + } + else + { + memcpy(user, dev, sizeof(struct up_dev_s)); + } + } + break; + + default: + *get_errno_ptr() = ENOTTY; + ret = ERROR; + break; + } + + return ret; +} + +/**************************************************************************** + * Name: up_receive + * + * Description: + * Called (usually) from the interrupt level to receive one + * character from the UART. Error bits associated with the + * receipt are provided in the the return 'status'. + * + ****************************************************************************/ + +static int up_receive(struct uart_dev_s *dev, uint32 *status) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + uint16 rxbufr; + + rxbufr = up_serialin(priv, STR71X_UART_RXBUFR_OFFSET); + *status = (uint32)priv->sr << 16 | rxbufr; + return rxbufr & 0xff; +} + +/**************************************************************************** + * Name: up_rxint + * + * Description: + * Call to enable or disable RX interrupts + * + ****************************************************************************/ + +static void up_rxint(struct uart_dev_s *dev, boolean enable) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + if (enable) + { + /* Receive an interrupt when the Rx FIFO is half full (or and IDLE + * timeout occurs. + */ + +#ifndef CONFIG_SUPPRESS_SERIAL_INTS + priv->ier |= (STR71X_UARTIER_RHF|STR71X_UARTIER_TIMEOUTIDLE); +#endif + } + else + { + priv->ier &= ~(STR71X_UARTIER_RHF|STR71X_UARTIER_TIMEOUTIDLE); + } + up_serialout(priv, STR71X_UART_IER_OFFSET, priv->ier); +} + +/**************************************************************************** + * Name: up_rxavailable + * + * Description: + * Return TRUE if the receive fifo is not empty + * + ****************************************************************************/ + +static boolean up_rxavailable(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + return ((up_serialin(priv, STR71X_UART_SR_OFFSET) & STR71X_UARTSR_RNE) != 0); +} + +/**************************************************************************** + * Name: up_send + * + * Description: + * This method will send one byte on the UART + * + ****************************************************************************/ + +static void up_send(struct uart_dev_s *dev, int ch) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + up_serialout(priv, STR71X_UART_TXBUFR_OFFSET, (uint16)ch); +} + +/**************************************************************************** + * Name: up_txint + * + * Description: + * Call to enable or disable TX interrupts + * + ****************************************************************************/ + +static void up_txint(struct uart_dev_s *dev, boolean enable) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + if (enable) + { + /* Set to receive an interrupt when the TX fifo is half emptied */ +#ifndef CONFIG_SUPPRESS_SERIAL_INTS + priv->ier |= STR71X_UARTSR_THE; +#endif + } + else + { + priv->ier &= ~STR71X_UARTSR_THE; + } + up_serialout(priv, STR71X_UART_IER_OFFSET, priv->ier); +} + +/**************************************************************************** + * Name: up_txready + * + * Description: + * Return TRUE if the tranmsit fifo is not full + * + ****************************************************************************/ + +static boolean up_txready(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + return ((up_serialin(priv, STR71X_UART_SR_OFFSET) & STR71X_UARTSR_TF) == 0); +} + +/**************************************************************************** + * Name: up_txempty + * + * Description: + * Return TRUE if the transmit fifo is empty + * + ****************************************************************************/ + +static boolean up_txempty(struct uart_dev_s *dev) +{ + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + return ((up_serialin(priv, STR71X_UART_SR_OFFSET) & STR71X_UARTSR_TE) != 0); +} + +/**************************************************************************** + * Public Funtions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_serialinit + * + * Description: + * Performs the low level UART initialization early in + * debug so that the serial console will be available + * during bootup. This must be called before up_serialinit. + * + ****************************************************************************/ + +void up_earlyserialinit(void) +{ + /* NOTE: All GPIO configuration for the UARTs was performed in + * up_lowsetup + */ + + /* Disable all UARTS */ + + up_disableuartint(TTYS0_DEV.priv, NULL); +#ifdef TTYS1_DEV + up_disableuartint(TTYS1_DEV.priv, NULL); +#endif +#ifdef TTYS2_DEV + up_disableuartint(TTYS2_DEV.priv, NULL); +#endif +#ifdef TTYS3_DEV + up_disableuartint(TTYS3_DEV.priv, NULL); +#endif + + /* Configuration whichever one is the console */ + +#ifdef HAVE_CONSOLE + CONSOLE_DEV.isconsole = TRUE; + up_setup(&CONSOLE_DEV); +#endif +} + +/**************************************************************************** + * Name: up_serialinit + * + * Description: + * Register serial console and serial ports. This assumes + * that up_earlyserialinit was called previously. + * + ****************************************************************************/ + +void up_serialinit(void) +{ + /* Register the console */ + +#ifdef HAVE_CONSOLE + (void)uart_register("/dev/console", &CONSOLE_DEV); +#endif + + /* Register all UARTs */ + + (void)uart_register("/dev/ttyS0", &TTYS0_DEV); +#ifdef TTYS1_DEV + (void)uart_register("/dev/ttyS1", &TTYS1_DEV); +#endif +#ifdef TTYS2_DEV + (void)uart_register("/dev/ttyS2", &TTYS2_DEV); +#endif +#ifdef TTYS3_DEV + (void)uart_register("/dev/ttyS3", &TTYS3_DEV); +#endif +} + +/**************************************************************************** + * Name: up_putc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +int up_putc(int ch) +{ + struct up_dev_s *priv = (struct up_dev_s*)CONSOLE_DEV.priv; + ubyte ier; + + up_disableuartint(priv, &ier); + up_waittxnotfull(priv); + up_serialout(priv, STR71X_UART_THR_OFFSET, (ubyte)ch); + + /* Check for LF */ + + if (ch == '\n') + { + /* Add CR */ + + up_waittxnotfull(priv); + up_serialout(priv, STR71X_UART_THR_OFFSET, '\r'); + } + + up_waittxnotfull(priv); + up_restoreuartint(priv, ier); + return ch; +} + +#else /* CONFIG_USE_SERIALDRIVER */ + +/**************************************************************************** + * Name: up_putc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +int up_putc(int ch) +{ + /* Check for LF */ + + if (ch == '\n') + { + /* Add CR */ + + up_lowputc('\r'); + } + + up_lowputc(ch); + return ch; +} + +#endif /* CONFIG_USE_SERIALDRIVER */ diff --git a/nuttx/arch/arm/src/str71x/str71x_uart.h b/nuttx/arch/arm/src/str71x/str71x_uart.h index 2533f8e78..fa602997f 100644 --- a/nuttx/arch/arm/src/str71x/str71x_uart.h +++ b/nuttx/arch/arm/src/str71x/str71x_uart.h @@ -126,13 +126,13 @@ #define STR71X_UARTCR_MODE8BIT (0x0001) /* 8-bit */ #define STR71X_UARTCR_MODE7BITP (0x0003) /* 7-bit with parity bit */ #define STR71X_UARTCR_MODE9BIT (0x0004) /* 9-bit */ -#define STR71X_UARTCR_MODE8BIT (0x0005) /* 8-bit with wakeup bit */ -#define STR71X_UARTCR_MODE8BIT (0x0007) /* 8-bit with parity bit */ +#define STR71X_UARTCR_MODE8BITWU (0x0005) /* 8-bit with wakeup bit */ +#define STR71X_UARTCR_MODE8BITP (0x0007) /* 8-bit with parity bit */ #define STR71X_UARTCR_STOPBITSMASK (0x0018) /* Bits 3-4: Stop bits */ -#define STR71X_UARTCR_STOPBIT0 (0x0000) /* 0.5 stop bits */ -#define STR71X_UARTCR_STOPBIT1 (0x0008) /* 1 stop bit */ -#define STR71X_UARTCR_STOPBIT0 (0x0010) /* 1.5 stop bits */ -#define STR71X_UARTCR_STOPBIT0 (0x0018) /* 2 stop bits */ +#define STR71X_UARTCR_STOPBIT05 (0x0000) /* 0.5 stop bits */ +#define STR71X_UARTCR_STOPBIT10 (0x0008) /* 1.0 stop bit */ +#define STR71X_UARTCR_STOPBIT15 (0x0010) /* 1.5 stop bits */ +#define STR71X_UARTCR_STOPBIT20 (0x0018) /* 2.0 stop bits */ #define STR71X_UARTCR_PARITYODD (0x0020) /* Bit 5: #define STR71X_UARTCR_LOOPBACK (0x0040) /* Bit 6: #define STR71X_UARTCR_RUN (0x0080) /* Bit 7: @@ -151,6 +151,7 @@ #define STR71X_UARTIER_TIMEOUTNE (0x0040) /* Bit 6: Time out not empty*/ #define STR71X_UARTIER_TIMEOUTIDLE (0x0080) /* Bit 7: Timeout out idle */ #define STR71X_UARTIER_RHF (0x0100) /* Bit 8: Rx half full */ +#define STR71X_UIRTIER_ALL (0x01ff) /* All interrupt bits */ /* UART status register (SR) */ -- cgit v1.2.3