summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-04-01 11:24:15 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-04-01 11:24:15 -0600
commit610e2aa0c224e2936fe8009ef4a2351ce607067a (patch)
tree7fae81997294d8d2cdb35995f64e976413a2ca67
parenta38c6df093edba13268a94fffcf4534cce5bc7d6 (diff)
downloadnuttx-610e2aa0c224e2936fe8009ef4a2351ce607067a.tar.gz
nuttx-610e2aa0c224e2936fe8009ef4a2351ce607067a.tar.bz2
nuttx-610e2aa0c224e2936fe8009ef4a2351ce607067a.zip
SAMA5: Add support for DBGU. Xplained board now uses DBGU for the serial console
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/arch/arm/src/calypso/Kconfig1
-rw-r--r--nuttx/arch/arm/src/sama5/Kconfig37
-rw-r--r--nuttx/arch/arm/src/sama5/Make.defs4
-rw-r--r--nuttx/arch/arm/src/sama5/sam_dbgu.c631
-rw-r--r--nuttx/arch/arm/src/sama5/sam_dbgu.h109
-rw-r--r--nuttx/arch/arm/src/sama5/sam_lowputc.c81
-rw-r--r--nuttx/arch/arm/src/sama5/sam_serial.c106
-rw-r--r--nuttx/arch/z80/src/z180/Kconfig1
-rw-r--r--nuttx/configs/sama5d3-xplained/README.txt65
-rw-r--r--nuttx/configs/sama5d3-xplained/nsh/defconfig111
-rw-r--r--nuttx/configs/sama5d3x-ek/README.txt25
-rw-r--r--nuttx/drivers/lcd/Kconfig2
-rw-r--r--nuttx/drivers/serial/Kconfig28
-rw-r--r--nuttx/drivers/usbdev/Kconfig2
-rw-r--r--nuttx/sched/clock_gettime.c6
16 files changed, 1070 insertions, 144 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 40ca2db1f..54078ff61 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -7104,4 +7104,7 @@
arm_head.S (2014-3-31).
* arch/arm/src/sama5/chip/sam_dbgu.h: Add SAMA5D3 DBGU definition
header file (2014-3031).
-
+ * arch/arm/src/sama5/sam_dbgu.c and .h: Add support for the SAMA5D3
+ DBGU (2014-4-1).
+ * configs/sama5d3-xplained/nsh: Configurations now use the DBGU for
+ the serial console (instead of USART1) (2014-4-1).
diff --git a/nuttx/arch/arm/src/calypso/Kconfig b/nuttx/arch/arm/src/calypso/Kconfig
index ac6179171..287494cc4 100644
--- a/nuttx/arch/arm/src/calypso/Kconfig
+++ b/nuttx/arch/arm/src/calypso/Kconfig
@@ -96,6 +96,7 @@ endmenu
choice
prompt "Serial Console Selection"
default SERIAL_CONSOLE_NONE
+ depends on DEV_CONSOLE
# See drivers/Kconfig
config USE_SERCOMM_CONSOLE
diff --git a/nuttx/arch/arm/src/sama5/Kconfig b/nuttx/arch/arm/src/sama5/Kconfig
index 4e1b0a1c3..899e8a6dc 100644
--- a/nuttx/arch/arm/src/sama5/Kconfig
+++ b/nuttx/arch/arm/src/sama5/Kconfig
@@ -345,6 +345,43 @@ config SAMA5_PIOE_IRQ
endif # PIO_IRQ
+menu "DBGU Configuration"
+ depends on SAMA5_DBGU
+
+config SAMA5_DBGU_CONSOLE
+ bool "DBGU serial console"
+ ---help---
+ Select to use the DBGU as the serial console.
+
+config SAMA5_DBGU_RXBUFSIZE
+ int "Receive buffer size"
+ default 256
+ ---help---
+ Characters are buffered as they are received. This specifies
+ the size of the receive buffer.
+
+config SAMA5_DBGU_TXBUFSIZE
+ int "Transmit buffer size"
+ default 256
+ ---help---
+ Characters are buffered before being sent. This specifies
+ the size of the transmit buffer.
+
+config SAMA5_DBGU_BAUD
+ int "BAUD rate"
+ default 115200
+ ---help---
+ The configured BAUD of the UART.
+
+config SAMA5_DBGU_PARITY
+ int "Parity setting"
+ default 0
+ range 0 2
+ ---help---
+ 0=no parity, 1=odd parity, 2=even parity
+
+endmenu #DBGU Configuration
+
if SAMA5_LCDC
menu "LCDC Configuration"
diff --git a/nuttx/arch/arm/src/sama5/Make.defs b/nuttx/arch/arm/src/sama5/Make.defs
index ced54cb32..fd657060b 100644
--- a/nuttx/arch/arm/src/sama5/Make.defs
+++ b/nuttx/arch/arm/src/sama5/Make.defs
@@ -119,6 +119,10 @@ ifeq ($(CONFIG_SAMA5_WDT),y)
CHIP_CSRCS += sam_wdt.c
endif
+ifeq ($(CONFIG_SAMA5_DBGU),y)
+CHIP_CSRCS += sam_dbgu.c
+endif
+
ifeq ($(CONFIG_SAMA5_TRNG),y)
CHIP_CSRCS += sam_trng.c
endif
diff --git a/nuttx/arch/arm/src/sama5/sam_dbgu.c b/nuttx/arch/arm/src/sama5/sam_dbgu.c
new file mode 100644
index 000000000..4a86921c0
--- /dev/null
+++ b/nuttx/arch/arm/src/sama5/sam_dbgu.c
@@ -0,0 +1,631 @@
+/****************************************************************************
+ * arch/arm/src/sama5/sam_dbgu.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <stdint.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <semaphore.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <nuttx/serial/serial.h>
+
+#include <arch/serial.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+#include "os_internal.h"
+
+#include "chip.h"
+#include "chip/sam_dbgu.h"
+#include "chip/sam_pinmap.h"
+#include "sam_pio.h"
+#include "sam_dbgu.h"
+
+#ifdef CONFIG_SAMA5_DBGU
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+#ifdef USE_SERIALDRIVER
+struct dbgu_dev_s
+{
+ uint32_t sr; /* Saved status bits */
+};
+#endif
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int dbgu_setup(struct uart_dev_s *dev);
+
+#ifdef USE_SERIALDRIVER
+static void dbgu_shutdown(struct uart_dev_s *dev);
+static int dbgu_attach(struct uart_dev_s *dev);
+static void dbgu_detach(struct uart_dev_s *dev);
+static int dbgu_interrupt(int irq, void *context);
+static int dbgu_ioctl(struct file *filep, int cmd, unsigned long arg);
+static int dbgu_receive(struct uart_dev_s *dev, uint32_t *status);
+static void dbgu_rxint(struct uart_dev_s *dev, bool enable);
+static bool dbgu_rxavailable(struct uart_dev_s *dev);
+static void dbgu_send(struct uart_dev_s *dev, int ch);
+static void dbgu_txint(struct uart_dev_s *dev, bool enable);
+static bool dbgu_txready(struct uart_dev_s *dev);
+static bool dbgu_txempty(struct uart_dev_s *dev);
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+static const struct uart_ops_s g_uart_ops =
+{
+ .setup = dbgu_setup,
+ .shutdown = dbgu_shutdown,
+ .attach = dbgu_attach,
+ .detach = dbgu_detach,
+ .ioctl = dbgu_ioctl,
+ .receive = dbgu_receive,
+ .rxint = dbgu_rxint,
+ .rxavailable = dbgu_rxavailable,
+ .send = dbgu_send,
+ .txint = dbgu_txint,
+ .txready = dbgu_txready,
+ .txempty = dbgu_txempty,
+};
+
+/* DBGU I/O buffers */
+
+static char g_dbgu_rxbuffer[CONFIG_SAMA5_DBGU_RXBUFSIZE];
+static char g_dbgu_txbuffer[CONFIG_SAMA5_DBGU_TXBUFSIZE];
+
+/* This describes the private state of the DBGU port */
+
+static struct dbgu_dev_s g_dbgu_priv;
+
+/* This describes the state of the DBGU port as is visible from the upper
+ * half serial driver.
+ */
+
+static uart_dev_t g_dbgu_port =
+{
+ .recv =
+ {
+ .size = CONFIG_SAMA5_DBGU_RXBUFSIZE,
+ .buffer = g_dbgu_rxbuffer,
+ },
+ .xmit =
+ {
+ .size = CONFIG_SAMA5_DBGU_TXBUFSIZE,
+ .buffer = g_dbgu_txbuffer,
+ },
+ .ops = &g_uart_ops,
+ .priv = &g_dbgu_priv,
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: dbgu_configure
+ *
+ * Description:
+ * Configure the DBGU baud, bits, parity, etc. This method is called the
+ * first time that the serial port is opened.
+ *
+ ****************************************************************************/
+
+static void dbgu_configure(void)
+{
+#ifndef CONFIG_SUPPRESS_UART_CONFIG
+ uint32_t regval;
+
+ /* Set up the mode register. Start with normal DBGU mode and the MCK
+ * as the timing source
+ */
+
+ regval = DBGU_MR_CHMODE_NORMAL;
+
+ /* OR in settings for the selected parity */
+
+#if CONFIG_SAMA5_DBGU_PARITY == 1
+ regval |= DBGU_MR_PAR_ODD;
+#elif CONFIG_SAMA5_DBGU_PARITY == 2
+ regval |= DBGU_MR_PAR_EVEN;
+#else
+ regval |= DBGU_MR_PAR_NONE;
+#endif
+
+ /* And save the new mode register value */
+
+ putreg32(regval, SAM_DBGU_MR);
+
+ /* Configure the console baud. NOTE: Oversampling by 8 is not supported.
+ * This may limit BAUD rates for lower DBGU clocks.
+ */
+
+ regval = (BOARD_MCK_FREQUENCY + (CONFIG_SAMA5_DBGU_BAUD << 3)) /
+ (CONFIG_SAMA5_DBGU_BAUD << 4);
+ putreg32(regval, SAM_DBGU_BRGR);
+
+ /* Enable receiver & transmitter */
+
+ putreg32((DBGU_CR_RXEN|DBGU_CR_TXEN), SAM_DBGU_CR);
+#endif
+}
+
+/****************************************************************************
+ * Name: dbgu_setup
+ *
+ * Description:
+ * Configure the DBGU baud, bits, parity, etc. This method is called the
+ * first time that the serial port is opened.
+ *
+ ****************************************************************************/
+
+static int dbgu_setup(struct uart_dev_s *dev)
+{
+#ifndef CONFIG_SUPPRESS_UART_CONFIG
+ /* The shutdown method will put the DBGU in a known, disabled state */
+
+ dbgu_shutdown(dev);
+
+ /* Then configure the DBGU */
+
+ dbgu_configure();
+#endif
+ return OK;
+}
+
+/****************************************************************************
+ * Name: dbgu_shutdown
+ *
+ * Description:
+ * Disable the DBGU. This method is called when the serial
+ * port is closed
+ *
+ ****************************************************************************/
+
+static void dbgu_shutdown(struct uart_dev_s *dev)
+{
+ irqstate_t flags;
+
+ /* The following must be atomic */
+
+ flags = irqsave();
+
+ /* Reset and disable receiver and transmitter */
+
+ putreg32((DBGU_CR_RSTRX|DBGU_CR_RSTTX|DBGU_CR_RXDIS|DBGU_CR_TXDIS), SAM_DBGU_CR);
+
+ /* Disable all interrupts */
+
+ putreg32(DBGU_INT_ALLINTS, SAM_DBGU_IDR);
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: dbgu_attach
+ *
+ * Description:
+ * Configure the DBGU 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 dbgu_attach(struct uart_dev_s *dev)
+{
+ int ret;
+
+ /* Attach and enable the IRQ */
+
+ ret = irq_attach(SAM_IRQ_DBGU, dbgu_interrupt);
+ if (ret == OK)
+ {
+ /* Enable the interrupt (RX and TX interrupts are still disabled
+ * in the DBGU
+ */
+
+ up_enable_irq(SAM_IRQ_DBGU);
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: dbgu_detach
+ *
+ * Description:
+ * Detach DBGU 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 dbgu_detach(struct uart_dev_s *dev)
+{
+ up_disable_irq(SAM_IRQ_DBGU);
+ irq_detach(SAM_IRQ_DBGU);
+}
+
+/****************************************************************************
+ * Name: dbgu_interrupt
+ *
+ * Description:
+ * This is the DBGU 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
+ * appropriate uart_dev_s structure in order to call these functions.
+ *
+ ****************************************************************************/
+
+static int dbgu_interrupt(int irq, void *context)
+{
+ struct uart_dev_s *dev = &g_dbgu_port;
+ struct dbgu_dev_s *priv = (struct dbgu_dev_s*)dev->priv;
+ uint32_t pending;
+ uint32_t imr;
+ int passes;
+ bool handled;
+
+ /* Loop until there are no characters to be transferred or, until we have
+ * been looping for a long time.
+ */
+
+ handled = true;
+ for (passes = 0; passes < 256 && handled; passes++)
+ {
+ handled = false;
+
+ /* Get the DBGU/DBGU status (we are only interested in the unmasked interrupts). */
+
+ priv->sr = getreg32(SAM_DBGU_SR); /* Save for error reporting */
+ imr = getreg32(SAM_DBGU_IMR); /* Interrupt mask */
+ pending = priv->sr & imr; /* Mask out disabled interrupt sources */
+
+ /* Handle an incoming, receive byte. RXRDY: At least one complete character
+ * has been received and US_RHR has not yet been read.
+ */
+
+ if ((pending & DBGU_INT_RXRDY) != 0)
+ {
+ /* Received data ready... process incoming bytes */
+
+ uart_recvchars(dev);
+ handled = true;
+ }
+
+ /* Handle outgoing, transmit bytes. XRDY: There is no character in the
+ * US_THR.
+ */
+
+ if ((pending & DBGU_INT_TXRDY) != 0)
+ {
+ /* Transmit data register empty ... process outgoing bytes */
+
+ uart_xmitchars(dev);
+ handled = true;
+ }
+ }
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: dbgu_ioctl
+ *
+ * Description:
+ * All ioctl calls will be routed through this method
+ *
+ ****************************************************************************/
+
+static int dbgu_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+#ifdef CONFIG_SERIAL_TIOCSERGSTRUCT
+ struct inode *inode = filep->f_inode;
+ struct uart_dev_s *dev = inode->i_private;
+#endif
+ int ret = OK;
+
+ switch (cmd)
+ {
+#ifdef CONFIG_SERIAL_TIOCSERGSTRUCT
+ case TIOCSERGSTRUCT:
+ {
+ struct dbgu_dev_s *user = (struct dbgu_dev_s*)arg;
+ if (!user)
+ {
+ ret = -EINVAL;
+ }
+ else
+ {
+ memcpy(user, dev, sizeof(struct dbgu_dev_s));
+ }
+ }
+ break;
+#endif
+
+ default:
+ ret = -ENOTTY;
+ break;
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Name: dbgu_receive
+ *
+ * Description:
+ * Called (usually) from the interrupt level to receive one
+ * character from the DBGU. Error bits associated with the
+ * receipt are provided in the return 'status'.
+ *
+ ****************************************************************************/
+
+static int dbgu_receive(struct uart_dev_s *dev, uint32_t *status)
+{
+ struct dbgu_dev_s *priv = (struct dbgu_dev_s*)dev->priv;
+
+ /* Return the error information in the saved status */
+
+ *status = priv->sr;
+ priv->sr = 0;
+
+ /* Then return the actual received byte */
+
+ return (int)(getreg32(SAM_DBGU_RHR) & 0xff);
+}
+
+/****************************************************************************
+ * Name: dbgu_rxint
+ *
+ * Description:
+ * Call to enable or disable RXRDY interrupts
+ *
+ ****************************************************************************/
+
+static void dbgu_rxint(struct uart_dev_s *dev, bool enable)
+{
+ if (enable)
+ {
+ /* Receive an interrupt when their is anything in the Rx data register (or an Rx
+ * timeout occurs).
+ */
+
+#ifndef CONFIG_SUPPRESS_SERIAL_INTS
+ putreg32(DBGU_INT_RXRDY, SAM_DBGU_IER);
+#endif
+ }
+ else
+ {
+ putreg32(DBGU_INT_RXRDY, SAM_DBGU_IDR);
+ }
+}
+
+/****************************************************************************
+ * Name: dbgu_rxavailable
+ *
+ * Description:
+ * Return true if the receive holding register is not empty
+ *
+ ****************************************************************************/
+
+static bool dbgu_rxavailable(struct uart_dev_s *dev)
+{
+ return ((getreg32(SAM_DBGU_SR) & DBGU_INT_RXRDY) != 0);
+}
+
+/****************************************************************************
+ * Name: dbgu_send
+ *
+ * Description:
+ * This method will send one byte on the DBGU/DBGU
+ *
+ ****************************************************************************/
+
+static void dbgu_send(struct uart_dev_s *dev, int ch)
+{
+ putreg32((uint32_t)ch, SAM_DBGU_THR);
+}
+
+/****************************************************************************
+ * Name: dbgu_txint
+ *
+ * Description:
+ * Call to enable or disable TX interrupts
+ *
+ ****************************************************************************/
+
+static void dbgu_txint(struct uart_dev_s *dev, bool enable)
+{
+ irqstate_t flags;
+
+ flags = irqsave();
+ if (enable)
+ {
+ /* Set to receive an interrupt when the TX holding register register
+ * is empty
+ */
+
+#ifndef CONFIG_SUPPRESS_SERIAL_INTS
+ putreg32(DBGU_INT_TXRDY, SAM_DBGU_IER);
+
+ /* Fake a TX interrupt here by just calling uart_xmitchars() with
+ * interrupts disabled (note this may recurse).
+ */
+
+ uart_xmitchars(dev);
+#endif
+ }
+ else
+ {
+ /* Disable the TX interrupt */
+
+ putreg32(DBGU_INT_TXRDY, SAM_DBGU_IDR);
+ }
+
+ irqrestore(flags);
+}
+
+/****************************************************************************
+ * Name: dbgu_txready
+ *
+ * Description:
+ * Return true if the transmit holding register is empty (TXRDY)
+ *
+ ****************************************************************************/
+
+static bool dbgu_txready(struct uart_dev_s *dev)
+{
+ return ((getreg32(SAM_DBGU_SR) & DBGU_INT_TXRDY) != 0);
+ }
+
+/****************************************************************************
+ * Name: dbgu_txempty
+ *
+ * Description:
+ * Return true if the transmit holding and shift registers are empty
+ *
+ ****************************************************************************/
+
+static bool dbgu_txempty(struct uart_dev_s *dev)
+{
+ return ((getreg32(SAM_DBGU_SR) & DBGU_INT_TXEMPTY) != 0);
+}
+
+/****************************************************************************
+ * Name: sam_dbgu_devinitialize
+ *
+ * Description:
+ * Performs the low level DBGU initialization early in debug so that the
+ * DBGU console will be available during bootup. This must be called
+ * before getreg32it.
+ *
+ ****************************************************************************/
+
+void sam_dbgu_devinitialize(void)
+{
+ /* Disable all DBGU interrupts */
+
+ putreg32(DBGU_INT_ALLINTS, SAM_DBGU_IDR);
+
+#ifdef CONFIG_SAMA5_DBGU_CONSOLE
+ /* Configuration the DBGU as the the console */
+
+ g_dbgu_port.isconsole = true;
+ dbgu_configure();
+#endif
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_dbgu_register
+ *
+ * Description:
+ * Register DBBU console and serial port. This assumes that
+ * sam_dbgu_initialize() was called previously.
+ *
+ ****************************************************************************/
+
+void sam_dbgu_register(void)
+{
+ /* Register the console */
+
+#ifdef CONFIG_SAMA5_DBGU_CONSOLE
+ (void)uart_register("/dev/console", &g_dbgu_port);
+#endif
+
+ /* Register the DBGU serial device */
+
+ (void)uart_register("/dev/ttyDBGU", &g_dbgu_port);
+}
+
+#endif /* USE_SERIALDRIVER */
+
+/****************************************************************************
+ * Name: sam_dbgu_initialize
+ *
+ * Description:
+ * Performs the low level DBGU initialization early in debug so that the
+ * DBGU console will be available during bootup. This must be called
+ * before getreg32it.
+ *
+ ****************************************************************************/
+
+void sam_dbgu_initialize(void)
+{
+ /* Initialize DBGU pins */
+
+ (void)sam_configpio(PIO_DBGU_DRXD);
+ (void)sam_configpio(PIO_DBGU_DTXD);
+
+#if defined(USE_SERIALDRIVER)
+ /* Initialize the DBGU device driver */
+
+ sam_dbgu_devinitialize();
+#elif defined(CONFIG_SAMA5_DBGU_CONSOLE)
+ sam_dbgu_configure();
+#endif
+}
+
+#endif /* CONFIG_SAMA5_DBGU */
diff --git a/nuttx/arch/arm/src/sama5/sam_dbgu.h b/nuttx/arch/arm/src/sama5/sam_dbgu.h
new file mode 100644
index 000000000..f85ecbe55
--- /dev/null
+++ b/nuttx/arch/arm/src/sama5/sam_dbgu.h
@@ -0,0 +1,109 @@
+/****************************************************************************
+ * arch/arm/src/sama5/sam_dbgu.h
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_SAMA5_SAM_DBGU_H
+#define __ARCH_ARM_SRC_SAMA5_SAM_DBGU_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "up_internal.h"
+
+#ifdef CONFIG_SAMA5_DBGU
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Inline Functions
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_dbgu_initialize
+ *
+ * Description:
+ * Performs the low level DBGU initialization early in debug so that the
+ * DBGU console will be available during bootup.
+ *
+ ****************************************************************************/
+
+void sam_dbgu_initialize(void);
+
+/****************************************************************************
+ * Name: sam_dbgu_register
+ *
+ * Description:
+ * Register DBBU console and serial port. This assumes that
+ * sam_dbgu_initialize() was called previously.
+ *
+ ****************************************************************************/
+
+void sam_dbgu_register(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* CONFIG_SAMA5_DBGU */
+#endif /* __ARCH_ARM_SRC_SAMA5_SAM_DBGU_H */
diff --git a/nuttx/arch/arm/src/sama5/sam_lowputc.c b/nuttx/arch/arm/src/sama5/sam_lowputc.c
index ba2edff91..6931c6cee 100644
--- a/nuttx/arch/arm/src/sama5/sam_lowputc.c
+++ b/nuttx/arch/arm/src/sama5/sam_lowputc.c
@@ -49,9 +49,11 @@
#include "sam_pio.h"
#include "sam_periphclks.h"
+#include "sam_dbgu.h"
#include "sam_lowputc.h"
#include "chip/sam_uart.h"
+#include "chip/sam_dbgu.h"
#include "chip/sam_pinmap.h"
/**************************************************************************
@@ -79,57 +81,72 @@
/* Is there a serial console? It could be on UART0-1 or USART0-3 */
-#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_UART0)
+#if defined(CONFIG_SAMA5_DBGU_CONSOLE) && defined(CONFIG_SAMA5_DBGU)
+# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# undef HAVE_UART_CONSOLE
+#elif defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_UART0)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_USART0_SERIAL_CONSOLE
+# undef CONFIG_USART1_SERIAL_CONSOLE
+# undef CONFIG_USART2_SERIAL_CONSOLE
+# undef CONFIG_USART3_SERIAL_CONSOLE
+# define HAVE_UART_CONSOLE 1
#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_UART1)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# define HAVE_UART_CONSOLE 1
#elif defined(CONFIG_USART0_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_USART0)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# define HAVE_UART_CONSOLE 1
#elif defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_USART1)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# define HAVE_UART_CONSOLE 1
#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_USART2)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# define HAVE_UART_CONSOLE 1
#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_USART3)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# define HAVE_UART_CONSOLE 1
#else
# warning "No valid CONFIG_USARTn_SERIAL_CONSOLE Setting"
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# undef HAVE_CONSOLE
+# undef HAVE_UART_CONSOLE
#endif
/* The UART/USART modules are driven by the main clock (MCK). */
@@ -139,7 +156,13 @@
/* Select USART parameters for the selected console */
-#if defined(CONFIG_UART0_SERIAL_CONSOLE)
+#if defined(CONFIG_SAMA5_DBGU_CONSOLE)
+# define SAM_CONSOLE_VBASE SAM_DBGU_VBASE
+# define SAM_CONSOLE_BAUD CONFIG_SAMA5_DBGU_BAUD
+# define SAM_CONSOLE_BITS 8
+# define SAM_CONSOLE_PARITY CONFIG_SAMA5_DBGU_PARITY
+# define SAM_CONSOLE_2STOP 0
+#elif defined(CONFIG_UART0_SERIAL_CONSOLE)
# define SAM_CONSOLE_VBASE SAM_UART0_VBASE
# define SAM_CONSOLE_BAUD CONFIG_UART0_BAUD
# define SAM_CONSOLE_BITS CONFIG_UART0_BITS
@@ -247,7 +270,7 @@
void up_lowputc(char ch)
{
-#ifdef HAVE_CONSOLE
+#if defined(HAVE_UART_CONSOLE)
irqstate_t flags;
for (;;)
@@ -274,6 +297,31 @@ void up_lowputc(char ch)
irqrestore(flags);
}
+#elif defined(CONFIG_SAMA5_DBGU_CONSOLE)
+ irqstate_t flags;
+
+ for (;;)
+ {
+ /* Wait for the transmitter to be available */
+
+ while ((getreg32(SAM_DBGU_SR) & DBGU_INT_TXEMPTY) == 0);
+
+ /* Disable interrupts so that the test and the transmission are
+ * atomic.
+ */
+
+ flags = irqsave();
+ if ((getreg32(SAM_DBGU_SR) & DBGU_INT_TXEMPTY) != 0)
+ {
+ /* Send the character */
+
+ putreg32((uint32_t)ch, SAM_DBGU_THR);
+ irqrestore(flags);
+ return;
+ }
+
+ irqrestore(flags);
+ }
#endif
}
@@ -287,7 +335,7 @@ void up_lowputc(char ch)
int up_putc(int ch)
{
-#ifdef HAVE_CONSOLE
+#if defined(HAVE_UART_CONSOLE) || defined(CONFIG_SAMA5_DBGU_CONSOLE)
/* Check for LF */
if (ch == '\n')
@@ -298,9 +346,9 @@ int up_putc(int ch)
}
up_lowputc(ch);
-#endif
return ch;
}
+#endif
/**************************************************************************
* Name: sam_lowsetup
@@ -392,7 +440,8 @@ void sam_lowsetup(void)
#endif
/* Configure the console (only) */
-#if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
+
+#if defined(HAVE_UART_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
/* Reset and disable receiver and transmitter */
putreg32((UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS),
@@ -418,4 +467,10 @@ void sam_lowsetup(void)
putreg32((UART_CR_RXEN | UART_CR_TXEN),
SAM_CONSOLE_VBASE + SAM_UART_CR_OFFSET);
#endif
+
+#ifdef CONFIG_SAMA5_DBGU
+ /* Initialize the DBGU (might be the serial console) */
+
+ sam_dbgu_initialize();
+#endif
}
diff --git a/nuttx/arch/arm/src/sama5/sam_serial.c b/nuttx/arch/arm/src/sama5/sam_serial.c
index 0cd1ac681..ca7e46121 100644
--- a/nuttx/arch/arm/src/sama5/sam_serial.c
+++ b/nuttx/arch/arm/src/sama5/sam_serial.c
@@ -61,9 +61,11 @@
#include "chip.h"
#include "chip/sam_uart.h"
+#include "sam_dbgu.h"
+#include "sam_serial.h"
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
/* Some sanity checks *******************************************************/
@@ -87,10 +89,8 @@
/* Is there a USART/USART enabled? */
-#if !defined(CONFIG_SAMA5_UART0) && !defined(CONFIG_SAMA5_UART1) && \
- !defined(CONFIG_SAMA5_USART0) && !defined(CONFIG_SAMA5_USART1) && \
- !defined(CONFIG_SAMA5_USART2) && !defined(CONFIG_SAMA5_USART3)
-# error "No USARTs enabled"
+#if defined(CONFIG_SAMA5_UART0) || defined(CONFIG_SAMA5_UART1)
+# define HAVE_UART
#endif
#if defined(CONFIG_SAMA5_USART0) || defined(CONFIG_SAMA5_USART1) ||\
@@ -100,57 +100,72 @@
/* Is there a serial console? It could be on UART0-1 or USART0-3 */
-#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_UART0)
+#if defined(CONFIG_SAMA5_DBGU_CONSOLE) && defined(CONFIG_SAMA5_DBGU)
+# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# undef HAVE_UART_CONSOLE
+#elif defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_UART0)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_USART0_SERIAL_CONSOLE
+# undef CONFIG_USART1_SERIAL_CONSOLE
+# undef CONFIG_USART2_SERIAL_CONSOLE
+# undef CONFIG_USART3_SERIAL_CONSOLE
+# define HAVE_UART_CONSOLE 1
#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_UART1)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# define HAVE_UART_CONSOLE 1
#elif defined(CONFIG_USART0_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_USART0)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# define HAVE_UART_CONSOLE 1
#elif defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_USART1)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# define HAVE_UART_CONSOLE 1
#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_USART2)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# define HAVE_UART_CONSOLE 1
#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(CONFIG_SAMA5_USART3)
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
-# define HAVE_CONSOLE 1
+# define HAVE_UART_CONSOLE 1
#else
# warning "No valid CONFIG_USARTn_SERIAL_CONSOLE Setting"
+# undef CONFIG_SAMA5_DBGU_CONSOLE
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
-# undef HAVE_CONSOLE
+# undef HAVE_UART_CONSOLE
#endif
/* If we are not using the serial driver for the console, then we still must
@@ -159,6 +174,15 @@
#ifdef USE_SERIALDRIVER
+#undef HAVE_UART_CONSOLE
+#undef TTYS1_DEV
+#undef TTYS2_DEV
+#undef TTYS3_DEV
+#undef TTYS4_DEV
+#undef TTYS5_DEV
+
+#if defined(HAVE_UART) || defined(HAVE_USART)
+
/* Which UART/USART with be tty0/console and which tty1? tty2? tty3? tty4? tty5? */
/* First pick the console and ttys0. This could be any of UART0-1, USART0-3 */
@@ -589,33 +613,16 @@ static inline void up_serialout(struct up_dev_s *priv, int offset, uint32_t valu
}
/****************************************************************************
- * Name: up_restoreusartint
- ****************************************************************************/
-
-static inline void up_restoreusartint(struct up_dev_s *priv, uint32_t imr)
-{
- /* Restore the previous interrupt state */
-
- up_serialout(priv, SAM_UART_IMR_OFFSET, imr);
-}
-
-/****************************************************************************
* Name: up_disableallints
****************************************************************************/
-static void up_disableallints(struct up_dev_s *priv, uint32_t *imr)
+static void up_disableallints(struct up_dev_s *priv)
{
irqstate_t flags;
/* The following must be atomic */
flags = irqsave();
- if (imr)
- {
- /* Return the current interrupt mask */
-
- *imr = up_serialin(priv, SAM_UART_IMR_OFFSET);
- }
/* Disable all interrupts */
@@ -748,7 +755,7 @@ static void up_shutdown(struct uart_dev_s *dev)
/* Disable all interrupts */
- up_disableallints(priv, NULL);
+ up_disableallints(priv);
}
/****************************************************************************
@@ -782,6 +789,7 @@ static int up_attach(struct uart_dev_s *dev)
up_enable_irq(priv->irq);
}
+
return ret;
}
@@ -810,7 +818,7 @@ static void up_detach(struct uart_dev_s *dev)
* 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.
+ * appropriate uart_dev_s structure in order to call these functions.
*
****************************************************************************/
@@ -1081,7 +1089,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
* Name: up_txready
*
* Description:
- * Return true if the tranmsit holding register is empty (TXRDY)
+ * Return true if the transmit holding register is empty (TXRDY)
*
****************************************************************************/
@@ -1105,6 +1113,8 @@ static bool up_txempty(struct uart_dev_s *dev)
return ((up_serialin(priv, SAM_UART_SR_OFFSET) & UART_INT_TXEMPTY) != 0);
}
+#endif /* HAVE_UART || HAVE_USART */
+
/****************************************************************************
* Public Functions
****************************************************************************/
@@ -1127,26 +1137,28 @@ void sam_earlyserialinit(void)
/* Disable all USARTS */
- up_disableallints(TTYS0_DEV.priv, NULL);
+#ifdef TTYS0_DEV
+ up_disableallints(TTYS0_DEV.priv);
+#endif
#ifdef TTYS1_DEV
- up_disableallints(TTYS1_DEV.priv, NULL);
+ up_disableallints(TTYS1_DEV.priv);
#endif
#ifdef TTYS2_DEV
- up_disableallints(TTYS2_DEV.priv, NULL);
+ up_disableallints(TTYS2_DEV.priv);
#endif
#ifdef TTYS3_DEV
- up_disableallints(TTYS3_DEV.priv, NULL);
+ up_disableallints(TTYS3_DEV.priv);
#endif
#ifdef TTYS4_DEV
- up_disableallints(TTYS4_DEV.priv, NULL);
+ up_disableallints(TTYS4_DEV.priv);
#endif
#ifdef TTYS5_DEV
- up_disableallints(TTYS5_DEV.priv, NULL);
+ up_disableallints(TTYS5_DEV.priv);
#endif
/* Configuration whichever one is the console */
-#ifdef HAVE_CONSOLE
+#ifdef HAVE_UART_CONSOLE
CONSOLE_DEV.isconsole = true;
up_setup(&CONSOLE_DEV);
#endif
@@ -1165,13 +1177,15 @@ void up_serialinit(void)
{
/* Register the console */
-#ifdef HAVE_CONSOLE
+#ifdef HAVE_UART_CONSOLE
(void)uart_register("/dev/console", &CONSOLE_DEV);
#endif
- /* Register all USARTs */
+ /* Register all UARTs/USARTs */
+#ifdef TTYS0_DEV
(void)uart_register("/dev/ttyS0", &TTYS0_DEV);
+#endif
#ifdef TTYS1_DEV
(void)uart_register("/dev/ttyS1", &TTYS1_DEV);
#endif
@@ -1187,6 +1201,12 @@ void up_serialinit(void)
#ifdef TTYS5_DEV
(void)uart_register("/dev/ttyS5", &TTYS5_DEV);
#endif
+
+/* Register the DBGU as well */
+
+#ifdef CONFIG_SAMA5_DBGU
+ sam_dbgu_register();
+#endif
}
#endif /* USE_SERIALDRIVER */
diff --git a/nuttx/arch/z80/src/z180/Kconfig b/nuttx/arch/z80/src/z180/Kconfig
index 93291ead2..8436241ee 100644
--- a/nuttx/arch/z80/src/z180/Kconfig
+++ b/nuttx/arch/z80/src/z180/Kconfig
@@ -236,6 +236,7 @@ endmenu
choice
prompt "Serial console"
default NO_SERIAL_CONSOLE
+ depends on DEV_CONSOLE
config Z180_UART0_SERIAL_CONSOLE
bool "UART0"
diff --git a/nuttx/configs/sama5d3-xplained/README.txt b/nuttx/configs/sama5d3-xplained/README.txt
index 507cf43b2..966ffa2a1 100644
--- a/nuttx/configs/sama5d3-xplained/README.txt
+++ b/nuttx/configs/sama5d3-xplained/README.txt
@@ -483,7 +483,7 @@ Programming U-Boot
- Press the "Send File Name" Browse button
- Choose u-boot.bin binary file and press Open
- Enter the proper address on media in the Address text field:
- 0x00200000
+ 0x00040000
- Press the "Send File" button
- Close SAM-BA, remove the USB Device cable.
@@ -660,10 +660,6 @@ Serial Console
J20 SDA 20 PE19 USART3 TXD3
J20 SCL 21 PE18 USART3 RXD3
- By default USART1 is used as the NuttX serial console in all
- configurations (unless otherwise noted). USART1 is provided at TTL
- levels at pins TXD0 and TXD1 of J20.
-
DBGU Interface
--------------
@@ -679,7 +675,10 @@ Serial Console
5 PE14 (available)
6 GND
- The DBGU is not used by NuttX.
+ By default the DBUG is used as the NuttX serial console in all
+ configurations (unless otherwise noted). The DBGU is available at
+ logic levels at pins RXD and TXD of the DEBUG connector (J23). GND
+ is available at J23 and +3.3V is available from J14
Networking
==========
@@ -855,15 +854,21 @@ AT25 Serial FLASH
Connections
-----------
- Both the SAMA5D3-Xplained board supports an options Serial DataFlash. The
- SPI connection is as follows:
+ The SAMA5D3-Xplained board supports an options Serial DataFlash connected
+ at MN8. The SPI connection is as follows:
+
+ MN8 SAMA5
+ ------------- -----------------------------------------------
+ PIN FUNCTION PIO FUNCTION
+ --- --------- ----- -----------------------------------------
+ 5 SI PD11 SPI0_MOSI
+ 2 SO PD10 SPI0_MIS0
+ 6 SCK PD12 SPI0_SPCK
+ 1 /CS PD13 if jumper JP6 is closed.
- AT25DF321A SAMA5
- --------------- -----------------------------------------------
- SI PD11 SPI0_MOSI
- SO PD10 SPI0_MIS0
- SCK PD12 SPI0_SPCK
- /CS PD13 if jumper JP6 is closed.
+ NOTE: The MN8 is not populated on my SAMAD3 Xplained board. So, as a
+ result, these instructions would only apply if you were to have an AT25
+ Serial DataFlash installed in MN8.
Configuration
-------------
@@ -897,7 +902,7 @@ AT25 Serial FLASH
CONFIG_SAMA5D3XPLAINED_AT25_AUTOMOUNT=y : Mounts AT25 for NSH
CONFIG_SAMA5D3XPLAINED_AT25_FTL=y : Create block driver for FAT
- NOTE that you must close JP6 in order to enable the AT25 FLASH chip select.
+ NOTE: that you must close JP6 in order to enable the AT25 FLASH chip select.
You can then format the AT25 FLASH for a FAT file system and mount the
file system at /mnt/at25 using these NSH commands:
@@ -914,9 +919,6 @@ AT25 Serial FLASH
nsh> cat /mnt/at25/atest.txt
This is a test
- NOTE: It appears that if Linux runs out of NAND, it will destroy the
- contents of the AT25.
-
HSMCI Card Slots
================
@@ -2391,10 +2393,10 @@ SAMA5D3-Xplained Configuration Options
Individual subsystems can be enabled:
- CONFIG_SAMA5_DBGU - Debug Unit Interrupt
- CONFIG_SAMA5_PIT - Periodic Interval Timer Interrupt
- CONFIG_SAMA5_WDT - Watchdog timer Interrupt
- CONFIG_SAMA5_HSMC - Multi-bit ECC Interrupt
+ CONFIG_SAMA5_DBGU - Debug Unit
+ CONFIG_SAMA5_PIT - Periodic Interval Timer
+ CONFIG_SAMA5_WDT - Watchdog timer
+ CONFIG_SAMA5_HSMC - Multi-bit ECC
CONFIG_SAMA5_SMD - SMD Soft Modem
CONFIG_SAMA5_USART0 - USART 0
CONFIG_SAMA5_USART1 - USART 1
@@ -2448,17 +2450,26 @@ SAMA5D3-Xplained Configuration Options
CONFIG_USART2_ISUART - USART2 is configured as a UART
CONFIG_USART3_ISUART - USART3 is configured as a UART
- ST91SAMA5 specific device driver settings
+ AT91SAMA5 specific device driver settings
+
+ CONFIG_SAMA5_DBGU_SERIAL_CONSOLE - selects the DBGU
+ for the console and ttyDBGU
+ CONFIG_SAMA5_DBGU_RXBUFSIZE - Characters are buffered as received.
+ This specific the size of the receive buffer
+ CONFIG_SAMA5_DBGU_TXBUFSIZE - Characters are buffered before
+ being sent. This specific the size of the transmit buffer
+ CONFIG_SAMA5_DBGU_BAUD - The configure BAUD of the DBGU.
+ CONFIG_SAMA5_DBGU_PARITY - 0=no parity, 1=odd parity, 2=even parity
CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=0,1,2,3) or UART
- m (m=4,5) for the console and ttys0 (default is the USART1).
+ m (m=4,5) for the console and ttys0 (default is the DBGU).
CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received.
This specific the size of the receive buffer
CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before
being sent. This specific the size of the transmit buffer
CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be
CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8.
- CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+ CONFIG_U[S]ARTn_PARITY - 0=no parity, 1=odd parity, 2=even parity
CONFIG_U[S]ARTn_2STOP - Two stop bits
AT91SAMA5 USB Host Configuration
@@ -2526,7 +2537,7 @@ Configurations
reconfiguration process.
2. Unless stated otherwise, all configurations generate console
- output on USART1 (J20).
+ output on the DBGU (J23).
3. All of these configurations use the Code Sourcery for Windows toolchain
(unless stated otherwise in the description of the configuration). That
@@ -2586,7 +2597,7 @@ Configurations
together.
NOTES:
- 1. This configuration uses the default USART1 serial console. That
+ 1. This configuration uses the default DBGU serial console. That
is easily changed by reconfiguring to (1) enable a different
serial peripheral, and (2) selecting that serial peripheral as
the console device.
diff --git a/nuttx/configs/sama5d3-xplained/nsh/defconfig b/nuttx/configs/sama5d3-xplained/nsh/defconfig
index 95a81b5d1..08f30d5e2 100644
--- a/nuttx/configs/sama5d3-xplained/nsh/defconfig
+++ b/nuttx/configs/sama5d3-xplained/nsh/defconfig
@@ -139,7 +139,7 @@ CONFIG_ARCH_CHIP_ATSAMA5D36=y
#
# SAMA5 Peripheral Support
#
-# CONFIG_SAMA5_DBGU is not set
+CONFIG_SAMA5_DBGU=y
# CONFIG_SAMA5_PIT is not set
# CONFIG_SAMA5_WDT is not set
# CONFIG_SAMA5_RTC is not set
@@ -148,7 +148,7 @@ CONFIG_SAMA5_HSMC=y
# CONFIG_SAMA5_UART0 is not set
# CONFIG_SAMA5_UART1 is not set
# CONFIG_SAMA5_USART0 is not set
-CONFIG_SAMA5_USART1=y
+# CONFIG_SAMA5_USART1 is not set
# CONFIG_SAMA5_USART2 is not set
# CONFIG_SAMA5_USART3 is not set
# CONFIG_SAMA5_TWI0 is not set
@@ -183,6 +183,15 @@ CONFIG_SAMA5_USART1=y
# CONFIG_SAMA5_PIO_IRQ is not set
#
+# DBGU Configuration
+#
+CONFIG_SAMA5_DBGU_CONSOLE=y
+CONFIG_SAMA5_DBGU_RXBUFSIZE=256
+CONFIG_SAMA5_DBGU_TXBUFSIZE=256
+CONFIG_SAMA5_DBGU_BAUD=115200
+CONFIG_SAMA5_DBGU_PARITY=0
+
+#
# External Memory Configuration
#
# CONFIG_SAMA5_EBICS0 is not set
@@ -273,36 +282,70 @@ CONFIG_NSH_MMCSDMINOR=0
#
# RTOS Features
#
-# CONFIG_BOARD_INITIALIZE is not set
+CONFIG_DISABLE_OS_API=y
+# CONFIG_DISABLE_CLOCK is not set
+# CONFIG_DISABLE_POSIX_TIMERS is not set
+# CONFIG_DISABLE_PTHREAD is not set
+# CONFIG_DISABLE_SIGNALS is not set
+# CONFIG_DISABLE_MQUEUE is not set
+CONFIG_DISABLE_ENVIRON=y
+
+#
+# Clocks and Timers
+#
CONFIG_MSEC_PER_TICK=10
# CONFIG_SYSTEM_TIME64 is not set
-CONFIG_RR_INTERVAL=200
-# CONFIG_SCHED_CPULOAD is not set
-# CONFIG_SCHED_INSTRUMENTATION is not set
-CONFIG_TASK_NAME_SIZE=32
-# CONFIG_SCHED_HAVE_PARENT is not set
+# CONFIG_CLOCK_MONOTONIC is not set
# CONFIG_JULIAN_TIME is not set
CONFIG_START_YEAR=2014
CONFIG_START_MONTH=7
CONFIG_START_DAY=31
-CONFIG_DEV_CONSOLE=y
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=16
+CONFIG_PREALLOC_TIMERS=4
+
+#
+# Tasks and Scheduling
+#
+CONFIG_USER_ENTRYPOINT="nsh_main"
+CONFIG_RR_INTERVAL=200
+CONFIG_TASK_NAME_SIZE=32
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_MAX_TASKS=16
+# CONFIG_SCHED_HAVE_PARENT is not set
+CONFIG_SCHED_WAITPID=y
+
+#
+# Pthread Options
+#
# CONFIG_MUTEX_TYPES is not set
-# CONFIG_PRIORITY_INHERITANCE is not set
+CONFIG_NPTHREAD_KEYS=4
+
+#
+# Performance Monitoring
+#
+# CONFIG_SCHED_CPULOAD is not set
+# CONFIG_SCHED_INSTRUMENTATION is not set
+
+#
+# Files and I/O
+#
+CONFIG_DEV_CONSOLE=y
# CONFIG_FDCLONE_DISABLE is not set
# CONFIG_FDCLONE_STDIO is not set
CONFIG_SDCLONE_DISABLE=y
-CONFIG_SCHED_WAITPID=y
+CONFIG_NFILE_DESCRIPTORS=8
+CONFIG_NFILE_STREAMS=8
+CONFIG_NAME_MAX=32
+# CONFIG_PRIORITY_INHERITANCE is not set
+
+#
+# RTOS hooks
+#
+# CONFIG_BOARD_INITIALIZE is not set
# CONFIG_SCHED_STARTHOOK is not set
# CONFIG_SCHED_ATEXIT is not set
# CONFIG_SCHED_ONEXIT is not set
-CONFIG_USER_ENTRYPOINT="nsh_main"
-CONFIG_DISABLE_OS_API=y
-# CONFIG_DISABLE_CLOCK is not set
-# CONFIG_DISABLE_POSIX_TIMERS is not set
-# CONFIG_DISABLE_PTHREAD is not set
-# CONFIG_DISABLE_SIGNALS is not set
-# CONFIG_DISABLE_MQUEUE is not set
-CONFIG_DISABLE_ENVIRON=y
#
# Signal Numbers
@@ -313,19 +356,10 @@ CONFIG_SIG_SIGALARM=3
CONFIG_SIG_SIGCONDTIMEDOUT=16
#
-# Sizes of configurable things (0 disables)
+# POSIX Message Queue Options
#
-CONFIG_MAX_TASKS=16
-CONFIG_MAX_TASK_ARGS=4
-CONFIG_NPTHREAD_KEYS=4
-CONFIG_NFILE_DESCRIPTORS=8
-CONFIG_NFILE_STREAMS=8
-CONFIG_NAME_MAX=32
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_MQ_MAXMSGSIZE=32
-CONFIG_MAX_WDOGPARMS=2
-CONFIG_PREALLOC_WDOGS=16
-CONFIG_PREALLOC_TIMERS=4
#
# Stack and heap information
@@ -381,7 +415,7 @@ CONFIG_SERIAL=y
# CONFIG_ARCH_HAVE_SCI0 is not set
# CONFIG_ARCH_HAVE_SCI1 is not set
# CONFIG_ARCH_HAVE_USART0 is not set
-CONFIG_ARCH_HAVE_USART1=y
+# CONFIG_ARCH_HAVE_USART1 is not set
# CONFIG_ARCH_HAVE_USART2 is not set
# CONFIG_ARCH_HAVE_USART3 is not set
# CONFIG_ARCH_HAVE_USART4 is not set
@@ -393,23 +427,10 @@ CONFIG_ARCH_HAVE_USART1=y
#
# USART Configuration
#
-CONFIG_USART1_ISUART=y
-CONFIG_MCU_SERIAL=y
+# CONFIG_MCU_SERIAL is not set
CONFIG_STANDARD_SERIAL=y
-CONFIG_USART1_SERIAL_CONSOLE=y
+# CONFIG_USART1_SERIAL_CONSOLE is not set
# CONFIG_NO_SERIAL_CONSOLE is not set
-
-#
-# USART1 Configuration
-#
-CONFIG_USART1_RXBUFSIZE=256
-CONFIG_USART1_TXBUFSIZE=256
-CONFIG_USART1_BAUD=115200
-CONFIG_USART1_BITS=8
-CONFIG_USART1_PARITY=0
-CONFIG_USART1_2STOP=0
-# CONFIG_USART1_IFLOWCONTROL is not set
-# CONFIG_USART1_OFLOWCONTROL is not set
# CONFIG_SERIAL_IFLOWCONTROL is not set
# CONFIG_SERIAL_OFLOWCONTROL is not set
# CONFIG_USBDEV is not set
diff --git a/nuttx/configs/sama5d3x-ek/README.txt b/nuttx/configs/sama5d3x-ek/README.txt
index 15bb9adf2..18158b2b6 100644
--- a/nuttx/configs/sama5d3x-ek/README.txt
+++ b/nuttx/configs/sama5d3x-ek/README.txt
@@ -604,7 +604,7 @@ Programming U-Boot
- Press the "Send File Name" Browse button
- Choose u-boot.bin binary file and press Open
- Enter the proper address on media in the Address text field:
- 0x00200000
+ 0x00040000
- Press the "Send File" button
- Close SAM-BA, remove the USB Device cable.
@@ -2722,10 +2722,10 @@ SAMA5D3x-EK Configuration Options
Individual subsystems can be enabled:
- CONFIG_SAMA5_DBGU - Debug Unit Interrupt
- CONFIG_SAMA5_PIT - Periodic Interval Timer Interrupt
- CONFIG_SAMA5_WDT - Watchdog timer Interrupt
- CONFIG_SAMA5_HSMC - Multi-bit ECC Interrupt
+ CONFIG_SAMA5_DBGU - Debug Unit
+ CONFIG_SAMA5_PIT - Periodic Interval Timer
+ CONFIG_SAMA5_WDT - Watchdog timer
+ CONFIG_SAMA5_HSMC - Multi-bit ECC
CONFIG_SAMA5_SMD - SMD Soft Modem
CONFIG_SAMA5_USART0 - USART 0
CONFIG_SAMA5_USART1 - USART 1
@@ -2779,7 +2779,16 @@ SAMA5D3x-EK Configuration Options
CONFIG_USART2_ISUART - USART2 is configured as a UART
CONFIG_USART3_ISUART - USART3 is configured as a UART
- ST91SAMA5 specific device driver settings
+ AT91SAMA5 specific device driver settings
+
+ CONFIG_SAMA5_DBGU_SERIAL_CONSOLE - selects the DBGU
+ for the console and ttyDBGU
+ CONFIG_SAMA5_DBGU_RXBUFSIZE - Characters are buffered as received.
+ This specific the size of the receive buffer
+ CONFIG_SAMA5_DBGU_TXBUFSIZE - Characters are buffered before
+ being sent. This specific the size of the transmit buffer
+ CONFIG_SAMA5_DBGU_BAUD - The configure BAUD of the DBGU.
+ CONFIG_SAMA5_DBGU_PARITY - 0=no parity, 1=odd parity, 2=even parity
CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=0,1,2,3) or UART
m (m=4,5) for the console and ttys0 (default is the USART1).
@@ -2787,9 +2796,9 @@ SAMA5D3x-EK Configuration Options
This specific the size of the receive buffer
CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before
being sent. This specific the size of the transmit buffer
- CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be
+ CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART.
CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8.
- CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+ CONFIG_U[S]ARTn_PARITY - 0=no parity, 1=odd parity, 2=even parity
CONFIG_U[S]ARTn_2STOP - Two stop bits
AT91SAMA5 USB Host Configuration
diff --git a/nuttx/drivers/lcd/Kconfig b/nuttx/drivers/lcd/Kconfig
index 7ae1dd31e..46569b77e 100644
--- a/nuttx/drivers/lcd/Kconfig
+++ b/nuttx/drivers/lcd/Kconfig
@@ -9,7 +9,7 @@ config LCD_CONSOLE
bool "LCD console output"
default n
---help---
- It is possible to use an LCD to provide console output. This option
+ It is possible to use an SLCD to provide console output. This option
enables that possibility.
At present, only one architecture supports this option (M16C).
diff --git a/nuttx/drivers/serial/Kconfig b/nuttx/drivers/serial/Kconfig
index 88f9867fe..81f904272 100644
--- a/nuttx/drivers/serial/Kconfig
+++ b/nuttx/drivers/serial/Kconfig
@@ -7,6 +7,7 @@ config DEV_LOWCONSOLE
bool "Low-level console support"
default n
depends on ARCH_LOWPUTC
+ depends on DEV_CONSOLE
---help---
Use the simple, low-level, write-only serial console driver (minimal support)
@@ -39,6 +40,7 @@ config 16550_UART0_BAUD
config 16550_UART0_PARITY
int "16550 UART0 parity"
default 0
+ range 0 2
---help---
16550 UART0 parity. 0=None, 1=Odd, 2=Even. Default: None
@@ -103,6 +105,7 @@ config 16550_UART1_BAUD
config 16550_UART1_PARITY
int "16550 UART1 parity"
default 0
+ range 0 2
---help---
16550 UART1 parity. 0=None, 1=Odd, 2=Even. Default: None
@@ -167,6 +170,7 @@ config 16550_UART2_BAUD
config 16550_UART2_PARITY
int "16550 UART2 parity"
default 0
+ range 0 2
---help---
16550 UART2 parity. 0=None, 1=Odd, 2=Even. Default: None
@@ -231,6 +235,7 @@ config 16550_UART3_BAUD
config 16550_UART3_PARITY
int "16550 UART3 parity"
default 0
+ range 0 2
---help---
16550 UART3 parity. 0=None, 1=Odd, 2=Even. Default: None
@@ -277,6 +282,7 @@ endif
choice
prompt "16550 Serial Console"
default 16550_NO_SERIAL_CONSOLE
+ depends on DEV_CONSOLE
config 16550_UART0_SERIAL_CONSOLE
bool "16550 UART0 serial console"
@@ -531,6 +537,7 @@ choice
prompt "Serial console"
depends on MCU_SERIAL
default NO_SERIAL_CONSOLE
+ depends on DEV_CONSOLE
config UART_SERIAL_CONSOLE
bool "UART"
@@ -657,6 +664,7 @@ config UART_BITS
config UART_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -713,6 +721,7 @@ config UART0_BITS
config UART0_PARITY
int "Parity setting"
+ range 0 2
default 0
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -771,6 +780,7 @@ config USART0_BITS
config USART0_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -828,6 +838,7 @@ config UART1_BITS
config UART1_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -885,6 +896,7 @@ config USART1_BITS
config USART1_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -942,6 +954,7 @@ config UART2_BITS
config UART2_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -999,6 +1012,7 @@ config USART2_BITS
config USART2_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1056,6 +1070,7 @@ config UART3_BITS
config UART3_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1113,6 +1128,7 @@ config USART3_BITS
config USART3_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1170,6 +1186,7 @@ config UART4_BITS
config UART4_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1227,6 +1244,7 @@ config USART4_BITS
config USART4_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1284,6 +1302,7 @@ config UART5_BITS
config UART5_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1341,6 +1360,7 @@ config USART5_BITS
config USART5_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1398,6 +1418,7 @@ config USART6_BITS
config USART6_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1455,6 +1476,7 @@ config UART6_BITS
config UART6_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1512,6 +1534,7 @@ config USART7_BITS
config USART7_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1569,6 +1592,7 @@ config UART7_BITS
config UART7_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1626,6 +1650,7 @@ config USART8_BITS
config USART8_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1683,6 +1708,7 @@ config UART8_BITS
config UART8_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1740,6 +1766,7 @@ config SCI0_BITS
config SCI0_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
@@ -1783,6 +1810,7 @@ config SCI1_BITS
config SCI1_PARITY
int "Parity setting"
default 0
+ range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
diff --git a/nuttx/drivers/usbdev/Kconfig b/nuttx/drivers/usbdev/Kconfig
index 9fdc6c92c..d14ccfed5 100644
--- a/nuttx/drivers/usbdev/Kconfig
+++ b/nuttx/drivers/usbdev/Kconfig
@@ -191,6 +191,7 @@ if PL2303
config PL2303_CONSOLE
bool "PL2303 console device"
+ depends on DEV_CONSOLE
default n
---help---
Register the USB device as /dev/console so that is will be used
@@ -275,6 +276,7 @@ if CDCACM
config CDCACM_CONSOLE
bool "CDC/ACM console device"
+ depends on DEV_CONSOLE
default n
---help---
Register the USB device as /dev/console so that is will be used
diff --git a/nuttx/sched/clock_gettime.c b/nuttx/sched/clock_gettime.c
index e4b938539..ebc06548d 100644
--- a/nuttx/sched/clock_gettime.c
+++ b/nuttx/sched/clock_gettime.c
@@ -130,12 +130,6 @@ int clock_gettime(clockid_t clock_id, struct timespec *tp)
/* Return the elapsed time in seconds and nanoseconds */
nsecs = (msecs - (secs * MSEC_PER_SEC)) * NSEC_PER_MSEC;
- if (nsecs > NSEC_PER_SEC)
- {
- carry = nsecs / NSEC_PER_SEC;
- secs += carry;
- nsecs -= (carry * NSEC_PER_SEC);
- }
tp->tv_sec = (time_t)secs;
tp->tv_nsec = (long)nsecs;