summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-05-11 22:54:50 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-05-11 22:54:50 +0000
commit653293320a64e69454ee832e23bd2d9203580f92 (patch)
treea9312cdc29992361f51cbf4684cc651eca19716d
parent00bbb58c99ff728e82d633acd3b7059233801674 (diff)
downloadnuttx-653293320a64e69454ee832e23bd2d9203580f92.tar.gz
nuttx-653293320a64e69454ee832e23bd2d9203580f92.tar.bz2
nuttx-653293320a64e69454ee832e23bd2d9203580f92.zip
Add low-level console support for LM3S3918
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1770 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/lm3s/Make.defs2
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_gpio.h88
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_lowputc.c265
-rw-r--r--nuttx/arch/arm/src/str71x/str71x_lowputc.c6
4 files changed, 337 insertions, 24 deletions
diff --git a/nuttx/arch/arm/src/lm3s/Make.defs b/nuttx/arch/arm/src/lm3s/Make.defs
index ded34b380..28615cd8c 100644
--- a/nuttx/arch/arm/src/lm3s/Make.defs
+++ b/nuttx/arch/arm/src/lm3s/Make.defs
@@ -46,7 +46,7 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
up_undefinedinsn.c up_usestack.c
CHIP_ASRCS =
-CHIP_CSRCS = lm3s_start.c lm3s_syscontrol.c lm3s_irq.c
+CHIP_CSRCS = lm3s_start.c lm3s_syscontrol.c lm3s_irq.c lm3s_lowputc.c
ifdef CONFIG_NET
CHIP_CSRCS += lm3s_ethernet.c
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_gpio.h b/nuttx/arch/arm/src/lm3s/lm3s_gpio.h
index b4db728f8..16d3545eb 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_gpio.h
+++ b/nuttx/arch/arm/src/lm3s/lm3s_gpio.h
@@ -354,14 +354,20 @@
/* Bit-encoded input to lm3s_configgpio() *******************************************/
-#define GPIO_FUNC_SHIFT 30 /* Bit 31-30: GPIO function */
-#define GPIO_FUNC_MASK (3 << GPIO_FUNC_SHIFT)
-#define GPIO_FUNC_INPUT (0 << GPIO_FUNC_SHIFT) /* Normal GPIO input */
-#define GPIO_FUNC_OUTPUT (1 << GPIO_FUNC_SHIFT) /* Normal GPIO output */
-#define GPIO_FUNC_PERIPHERAL (2 << GPIO_FUNC_SHIFT) /* Peripheral function */
-#define GPIO_FUNC_INTERRUPT (3 << GPIO_FUNC_SHIFT) /* Interrupt function */
-
-#define GPIO_INT_SHIFT 27 /* Bits 29-27: Interrupt type */
+#define GPIO_FUNC_SHIFT 29 /* Bit 31-29: GPIO function */
+#define GPIO_FUNC_MASK (7 << GPIO_FUNC_SHIFT) /* (See table 9-1 in data sheet) */
+#define GPIO_FUNC_INPUT (0 << GPIO_FUNC_SHIFT) /* Digital GPIO input */
+#define GPIO_FUNC_OUTPUT (1 << GPIO_FUNC_SHIFT) /* Digital GPIO output */
+#define GPIO_FUNC_ODINPUT (2 << GPIO_FUNC_SHIFT) /* Open-drain GPIO input */
+#define GPIO_FUNC_ODOUTPUT (3 << GPIO_FUNC_SHIFT) /* Open-drain GPIO output */
+#define GPIO_FUNC_PFODIO (4 << GPIO_FUNC_SHIFT) /* Open-drain input/output (I2C) */
+#define GPIO_FUNC_PFINPUT (5 << GPIO_FUNC_SHIFT) /* Digital input (Timer, CCP) */
+#define GPIO_FUNC_PFOUTPUT (5 << GPIO_FUNC_SHIFT) /* Digital output (Timer, PWM, Comparator) */
+#define GPIO_FUNC_PFIO (5 << GPIO_FUNC_SHIFT) /* Digital input/output (SSI, UART) */
+#define GPIO_FUNC_ANINPUT (6 << GPIO_FUNC_SHIFT) /* Analog input (Comparator) */
+#define GPIO_FUNC_INTERRUPT (7 << GPIO_FUNC_SHIFT) /* Interrupt function */
+
+#define GPIO_INT_SHIFT 26 /* Bits 28-26: Interrupt type */
#define GPIO_INT_MASK (7 << GPIO_INT_SHIFT)
#define GPIO_INT_FALLINGEDGE (0 << GPIO_INT_SHIFT) /* Interrupt on falling edge */
#define GPIO_INT_RISINGEDGE (1 << GPIO_INT_SHIFT) /* Interrupt on rising edge */
@@ -369,22 +375,22 @@
#define GPIO_INT_LOWLEVEL (3 << GPIO_INT_SHIFT) /* Interrupt on low level */
#define GPIO_INT_HIGHLEVEL (4 << GPIO_INT_SHIFT) /* Interrupt on high level */
-#define GPIO_STRENGTH_SHIFT 25 /* Bits 26-25: Pad drive strength */
+#define GPIO_STRENGTH_SHIFT 24 /* Bits 25-24: Pad drive strength */
#define GPIO_STRENGTH_MASK (3 << GPIO_STRENGTH_SHIFT)
#define GPIO_STRENGTH_2MA (0 << GPIO_STRENGTH_SHIFT) /* 2mA pad drive strength */
#define GPIO_STRENGTH_4MA (1 << GPIO_STRENGTH_SHIFT) /* 4mA pad drive strength */
#define GPIO_STRENGTH_8MA (2 << GPIO_STRENGTH_SHIFT) /* 8mA pad drive strength */
#define GPIO_STRENGTH_8MASC (3 << GPIO_STRENGTH_SHIFT) /* 8mA Pad drive with slew rate control */
-#define GPIO_PADTYPE_SHIFT 22 /* Bits 22-24: Pad type */
-#define GPIO_PADTYPE_MASK (0 << GPIO_PADTYPE_SHIFT)
-#define GPIO_PADTYPE_STD (1 << GPIO_PADTYPE_SHIFT) /* Push-pull */
-#define GPIO_PADTYPE_STDWPU (2 << GPIO_PADTYPE_SHIFT) /* Push-pull with weak pull-up */
-#define GPIO_PADTYPE_STDWPD (3 << GPIO_PADTYPE_SHIFT) /* Push-pull with weak pull-down */
-#define GPIO_PADTYPE_OD (4 << GPIO_PADTYPE_SHIFT) /* Open-drain */
-#define GPIO_PADTYPE_ODWPU (5 << GPIO_PADTYPE_SHIFT) /* Open-drain with weak pull-up */
-#define GPIO_PADTYPE_ODWPD (6 << GPIO_PADTYPE_SHIFT) /* Open-drain with weak pull-down */
-#define GPIO_PADTYPE_ANALOG (7 << GPIO_PADTYPE_SHIFT) /* Analog comparator */
+#define GPIO_PADTYPE_SHIFT 21 /* Bits 21-23: Pad type */
+#define GPIO_PADTYPE_MASK (7 << GPIO_PADTYPE_SHIFT)
+#define GPIO_PADTYPE_STD (0 << GPIO_PADTYPE_SHIFT) /* Push-pull */
+#define GPIO_PADTYPE_STDWPU (1 << GPIO_PADTYPE_SHIFT) /* Push-pull with weak pull-up */
+#define GPIO_PADTYPE_STDWPD (2 << GPIO_PADTYPE_SHIFT) /* Push-pull with weak pull-down */
+#define GPIO_PADTYPE_OD (3 << GPIO_PADTYPE_SHIFT) /* Open-drain */
+#define GPIO_PADTYPE_ODWPU (4 << GPIO_PADTYPE_SHIFT) /* Open-drain with weak pull-up */
+#define GPIO_PADTYPE_ODWPD (5 << GPIO_PADTYPE_SHIFT) /* Open-drain with weak pull-down */
+#define GPIO_PADTYPE_ANALOG (6 << GPIO_PADTYPE_SHIFT) /* Analog comparator */
#define GPIO_VALUE_SHIFT 6 /* Bit 6: If output, inital value of output */
#define GPIO_VALUE_MASK (1 << GPIO_VALUE_SHIFT)
@@ -402,8 +408,50 @@
#define GPIO_PORTG (6 << GPIO_PORT_SHIFT) /* GPIOG */
#define GPIO_PORTH (7 << GPIO_PORT_SHIFT) /* GPIOH */
-#define GPIO_NUMBER_SHIFT 0 /* Bits 0-2: GPIO number: 0-7 */
-#define GPIO_NUMBER_MASK (0x07 << GPIO_NUMBER_SHIFT)
+#define GPIO_NUMBER_SHIFT 0 /* Bits 0-2: GPIO number: 0-7 */
+#define GPIO_NUMBER_MASK (7 << GPIO_NUMBER_SHIFT)
+
+/* The following lists the input value to lm3s_configgpio to setup the alternate,
+ * hardware function for each pin.
+ */
+
+#define GPIO_UART0_RX (GPIO_FUNC_PFINPUT | GPIO_PORTA | 0) /* PA0: UART 0 receive (U0Rx) */
+#define GPIO_UART0_TX (GPIO_FUNC_PFOUTPUT | GPIO_PORTA | 1) /* PA1: UART 0 transmit (U0Tx) */
+#define GPIO_SSI0_CLK (GPIO_FUNC_PFIO | GPIO_PORTA | 2) /* PA2: SSI0 clock (SSI0Clk) */
+#define GPIO_SSI0_FSS (GPIO_FUNC_PFIO | GPIO_PORTA | 3) /* PA3: SSI0 frame (SSI0Fss) */
+#define GPIO_SSI0_RX (GPIO_FUNC_PFINPUT | GPIO_PORTA | 4) /* PA4: SSI0 receive (SSI0Rx) */
+#define GPIO_SSI0_TX (GPIO_FUNC_PFOUTPUT | GPIO_PORTA | 5) /* PA5: SSI0 transmit (SSI0Tx) */
+#define GPIO_PWM1_CCP (GPIO_FUNC_PFIO | GPIO_PORTA | 6) /* PA6: Capture/Compare/PWM1 (CCP1) */
+#define GPIO_I2C1_SDA (GPIO_FUNC_PFODIO | GPIO_PORTA | 7) /* PA7: I2C1 data (I2C1SDA) */
+#define GPIO_PWM0_CCP (GPIO_FUNC_PFIO | GPIO_PORTB | 0) /* PB0: Capture/Compare/PWM0 (CCP0) */
+#define GPIO_PWM2_CCP (GPIO_FUNC_PFIO | GPIO_PORTB | 1) /* PB1: Capture/Compare/PWM2 (CCP2) */
+#define GPIO_I2C0_SCL (GPIO_FUNC_PFOUTPUT | GPIO_PORTB | 2) /* PB2: I2C0 clock (I2C0SCL) */
+#define GPIO_I2C0_SDA (GPIO_FUNC_PFODIO | GPIO_PORTB | 3) /* PB3: I2C0 data (I2C0SDA) */
+#define GPIO_CMP0_NIN (GPIO_FUNC_PFINPUT | GPIO_PORTB | 4) /* PB4: Analog comparator 0 negative input (C0-) */
+#define GPIO_CMP1_NIN (GPIO_FUNC_PFINPUT | GPIO_PORTB | 5) /* PB5: Analog comparator 1 negative input (C1-) */
+#define GPIO_CMP0_PIN (GPIO_FUNC_PFINPUT | GPIO_PORTB | 6) /* PB6: Analog comparator 0 positive input (C0+) */
+#define GPIO_JTAG_TRST (GPIO_FUNC_PFINPUT | GPIO_PORTB | 7) /* PB7: JTAG ~TRST */
+#define GPIO_JTAG_TCK (GPIO_FUNC_PFINPUT | GPIO_PORTC | 0) /* PC0: JTAG/SWD CLK */
+#define GPIO_JTAG_SWCLK (GPIO_FUNC_PFINPUT | GPIO_PORTC | 0) /* PC0: JTAG/SWD CLK */
+#define GPIO_JTAG_TMS (GPIO_FUNC_PFIO | GPIO_PORTC | 1) /* PC1: JTAG TMS */
+#define GPIO_JTAG_SWDIO (GPIO_FUNC_PFIO | GPIO_PORTC | 1) /* PC1: JTAG SWDIO */
+#define GPIO_JTAG_TDI (GPIO_FUNC_PFINPUT | GPIO_PORTC | 2) /* PC2: JTAG TDI */
+#define GPIO_JTAG_TDO (GPIO_FUNC_PFOUTPUT | GPIO_PORTC | 3) /* PC3: JTAG TDO */
+#define GPIO_JTAG_SWO (GPIO_FUNC_PFOUTPUT | GPIO_PORTC | 3) /* PC3: JTAG SWO */
+#define GPIO_PWM5_CCP (GPIO_FUNC_PFIO | GPIO_PORTC | 4) /* PC4: Capture/Compare/PWM5 (CCP5) */
+#define GPIO_CMP1_PIN (GPIO_FUNC_PFINPUT | GPIO_PORTC | 5) /* PC5: Analog comparator 1 positive input (C1+) */
+#define GPIO_CMP0_OUT (GPIO_FUNC_PFOUTPUT | GPIO_PORTC | 5) /* PC5: Analog comparator 0 output (C0o) */
+#define GPIO_PWM3_CCP (GPIO_FUNC_PFIO | GPIO_PORTC | 6) /* PC6: Capture/Compare/PWM3 (CCP3) */
+#define GPIO_PWM4_CCP (GPIO_FUNC_PFIO | GPIO_PORTC | 7) /* PC7: Capture/Compare/PWM4 (CCP4) */
+#define GPIO_UART1_RX (GPIO_FUNC_PFINPUT | GPIO_PORTD | 2) /* PD2: UART 1 receive (U1Rx) */
+#define GPIO_UART1_TX (GPIO_FUNC_PFOUTPUT | GPIO_PORTD | 3) /* PD3: UART 1 transmit (U1Tx) */
+#define GPIO_SSI1_CLK (GPIO_FUNC_PFIO1 | GPIO_PORTE | 0) /* PE0: SSI1 clock (SSI1Clk) */
+#define GPIO_SSI1_FSS (GPIO_FUNC_PFIO | GPIO_PORTE | 1) /* PE1: SSI1 frame (SSI1Fss) */
+#define GPIO_SSI1_RX (GPIO_FUNC_PFINPUT | GPIO_PORTE | 2) /* PE2: SSI1 receive (SSI1Rx) */
+#define GPIO_SSI1_TX (GPIO_FUNC_PFOUTPUT | GPIO_PORTE | 3) /* PE3: SSI1 transmit (SSI1Tx) */
+#define GPIO_ETHPHY_LED1 (GPIO_FUNC_PFOUTPUT | GPIO_PORTF | 2) /* PF2: LED1 */
+#define GPIO_ETHPHY_LED0 (GPIO_FUNC_PFOUTPUT | GPIO_PORTF | 3) /* PF3: LED0 */
+#define GPIO_I2C1_SCL (GPIO_FUNC_PFOUTPUT | GPIO_PORTG | 0) /* PG0: I2C1 clock (I2C1SCL) */
/************************************************************************************
* Public Types
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_lowputc.c b/nuttx/arch/arm/src/lm3s/lm3s_lowputc.c
new file mode 100644
index 000000000..554e57f7f
--- /dev/null
+++ b/nuttx/arch/arm/src/lm3s/lm3s_lowputc.c
@@ -0,0 +1,265 @@
+/**************************************************************************
+ * arch/arm/src/lm3s/lm3s_lowputc.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <nuttx/config.h>
+#include <sys/types.h>
+
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "chip.h"
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+/* Configuration **********************************************************/
+
+/* Is there a serial console? */
+
+#if defined(CONFIG_UART0_SERIAL_CONSOLE) && !defined(CONFIG_UART0_DISABLE)
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# define HAVE_CONSOLE 1
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_UART1_DISABLE)
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# define HAVE_CONSOLE 1
+#else
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef HAVE_CONSOLE
+#endif
+
+/* Select UART parameters for the selected console */
+
+#if defined(CONFIG_UART0_SERIAL_CONSOLE)
+# define LM3S_CONSOLE_BASE LM3S_UART0_BASE
+# define LM3S_CONSOLE_BAUD CONFIG_UART0_BAUD
+# define LM3S_CONSOLE_BITS CONFIG_UART0_BITS
+# define LM3S_CONSOLE_PARITY CONFIG_UART0_PARITY
+# define LM3S_CONSOLE_2STOP CONFIG_UART0_2STOP
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
+# define LM3S_CONSOLE_BASE LM3S_UART1_BASE
+# define LM3S_CONSOLE_BAUD CONFIG_UART1_BAUD
+# define LM3S_CONSOLE_BITS CONFIG_UART1_BITS
+# define LM3S_CONSOLE_PARITY CONFIG_UART1_PARITY
+# define LM3S_CONSOLE_2STOP CONFIG_UART1_2STOP
+#else
+# error "No CONFIG_UARTn_SERIAL_CONSOLE Setting"
+#endif
+
+/* Get LCRH settings */
+
+#if LM3S_CONSOLE_BITS == 5
+# define UART_LCRH_NBITS UART_LCRH_WLEN_5BITS
+#elif LM3S_CONSOLE_BITS == 6
+# define UART_LCRH_NBITS UART_LCRH_WLEN_6BITS
+#elif LM3S_CONSOLE_BITS == 7
+# define UART_LCRH_NBITS UART_LCRH_WLEN_7BITS
+#elif LM3S_CONSOLE_BITS == 8
+# define UART_LCRH_NBITS UART_LCRH_WLEN_8BITS
+#else
+# error "Number of bits not supported"
+#endif
+
+#if LM3S_CONSOLE_PARITY == 0
+# define UART_LCRH_PARITY (0)
+#elif LM3S_CONSOLE_PARITY == 1
+# define UART_LCRH_PARITY UART_LCRH_PEN
+#elif LM3S_CONSOLE_PARITY == 2
+# define UART_LCRH_PARITY (UART_LCRH_PEN|UART_LCRH_EPS)
+#else
+# error "Invalid parity selection"
+#endif
+
+#if LM3S_CONSOLE_2STOP != 0
+# define UART_LCRH_NSTOP UART_LCRH_STP2
+#else
+# define UART_LCRH_NSTOP (0)
+#endif
+
+#define UART_LCRH_VALUE (UART_LCRH_NBITS|UART_LCRH_PARITY|UART_LCRH_NSTOP|UART_LCRH_FEN)
+
+/* Calculate BAUD rate from PCLK1:
+ *
+ * "The baud-rate divisor is a 22-bit number consisting of a 16-bit integer and a 6-bit
+ * fractional part. The number formed by these two values is used by the baud-rate generator
+ * to determine the bit period. Having a fractional baud-rate divider allows the UART to
+ * generate all the standard baud rates.
+ *
+ * "The 16-bit integer is loaded through the UART Integer Baud-Rate Divisor (UARTIBRD)
+ * register ... and the 6-bit fractional part is loaded with the UART Fractional Baud-Rate
+ * Divisor (UARTFBRD) register... The baud-rate divisor (BRD) has the following relationship
+ * to the system clock (where BRDI is the integer part of the BRD and BRDF is the fractional
+ * part, separated by a decimal place.):
+ *
+ * "BRD = BRDI + BRDF = UARTSysClk / (16 * Baud Rate)
+ *
+ * "where UARTSysClk is the system clock connected to the UART. The 6-bit fractional number
+ * (that is to be loaded into the DIVFRAC bit field in the UARTFBRD register) can be calculated
+ * by taking the fractional part of the baud-rate divisor, multiplying it by 64, and adding 0.5
+ * to account for rounding errors:
+ *
+ * "UARTFBRD[DIVFRAC] = integer(BRDF * 64 + 0.5)
+ *
+ * "The UART generates an internal baud-rate reference clock at 16x the baud-rate (referred
+ * to as Baud16). This reference clock is divided by 16 to generate the transmit clock, and is
+ * used for error detection during receive operations.
+ *
+ * "Along with the UART Line Control, High Byte (UARTLCRH) register ..., the UARTIBRD and
+ * UARTFBRD registers form an internal 30-bit register. This internal register is only
+ * updated when a write operation to UARTLCRH is performed, so any changes to the baud-rate
+ * divisor must be followed by a write to the UARTLCRH register for the changes to take effect. ..."
+ */
+
+#define LM3S_BRDDEN (16 * LM3S_CONSOLE_BAUD)
+#define LM3S_BRDI (SYSCLK_FREQUENCY / LM3S_BRDDEN)
+#define LM3S_REMAINDER (SYSCLK_FREQUENCY - LM3S_BRDDEN * LM3S_BRDI)
+#define LM3S_DIVFRAC ((LM3S_REMAINDER * 64 + (LM3S_BRDDEN/2)) / LM3S_BRDDEN)
+
+/* For example: LM3S_CONSOLE_BAUD = 115,200, SYSCLK_FREQUENCY = 20,000,000:
+ *
+ * LM3S_BRDDEN = (16 * 115,200) = 1,843,200
+ * LM3S_BRDI = 20,000,000 / 1,843,200 = 10
+ * LM3S_REMAINDER = 20,000,000 - 1,843,200 * 10 = 1,568,000
+ * LM3S_DIVFRAC = (1,568,000 * 64 + 921,600) / 1,843,200 = 54
+ *
+ * Which should yied BAUD = 20,000,000 / (16 * (10 + 54/64)) = 115273.8
+ */
+
+/**************************************************************************
+ * 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)
+{
+#ifdef HAVE_CONSOLE
+ /* Wait until the TX FIFO is not full */
+
+ while ((getreg32(LM3S_CONSOLE_BASE+LM3S_UART_FR_OFFSET) & UART_FR_TXFF) != 0);
+
+ /* Then send the character */
+
+ putreg32((uint32)ch, LM3S_CONSOLE_BASE+LM3S_UART_DR_OFFSET);
+#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)
+{
+#ifdef HAVE_CONSOLE
+ uint16 ctl;
+
+ /* Enable the selected console device */
+ /* 1. Disable the UART by clearing the UARTEN bit in the UART CTL register */
+
+ ctl = getreg32(LM3S_CONSOLE_BASE+LM3S_UART_CTL_OFFSET);
+ ctl &= ~UART_CTL_UARTEN;
+ putreg32(ctl, LM3S_CONSOLE_BASE+LM3S_UART_CTL_OFFSET);
+
+ /* 2. Write the integer portion of the BRD to the UART IBRD register */
+
+ putreg32(LM3S_BRDI, LM3S_CONSOLE_BASE+LM3S_UART_IBRD_OFFSET);
+
+ /* 3. Write the fractional portion of the BRD to the UART FBRD register */
+
+ putreg32(LM3S_DIVFRAC, LM3S_CONSOLE_BASE+LM3S_UART_FBRD_OFFSET);
+
+ /* 4. Write the desired serial parameters to the UART LCRH register */
+
+ putreg32(UART_LCRH_VALUE, LM3S_CONSOLE_BASE+LM3S_UART_LCRH_OFFSET);
+
+ /* 5. Enable the UART by setting the UARTEN bit in the UART CTL register */
+
+ ctl |= UART_CTL_UARTEN;
+ putreg32(ctl, LM3S_CONSOLE_BASE+LM3S_UART_CTL_OFFSET);
+#endif
+
+ /* Configure GPIO pins to enable all UARTs in the configuration
+ * (the serial driver later depends on this configuration)
+ */
+
+#ifndef CONFIG_UART0_DISABLE
+ lm3x_configgpio(GPIO_UART0_RX);
+ lm3x_configgpio(GPIO_UART0_TX);
+#endif
+
+#ifndef CONFIG_UART1_DISABLE
+ lm3x_configgpio(GPIO_UART1_RX);
+ lm3x_configgpio(GPIO_UART1_TX);
+#endif
+}
+
+
diff --git a/nuttx/arch/arm/src/str71x/str71x_lowputc.c b/nuttx/arch/arm/src/str71x/str71x_lowputc.c
index d4f22bb11..d2dbc5747 100644
--- a/nuttx/arch/arm/src/str71x/str71x_lowputc.c
+++ b/nuttx/arch/arm/src/str71x/str71x_lowputc.c
@@ -86,7 +86,7 @@
# define STR71X_UART0_GPIO0_PC2BITS (0)
#endif
-#if CONFIG_STR71X_UART0
+#if CONFIG_STR71X_UART1
# 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)
@@ -98,7 +98,7 @@
# define STR71X_UART1_GPIO0_PC2BITS (0)
#endif
-#if CONFIG_STR71X_UART0
+#if CONFIG_STR71X_UART2
# 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)
@@ -110,7 +110,7 @@
# define STR71X_UART2_GPIO0_PC2BITS (0)
#endif
-#if CONFIG_STR71X_UART0
+#if CONFIG_STR71X_UART3
# 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)