You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@nuttx.apache.org by pr...@apache.org on 2020/09/14 12:23:57 UTC

[incubator-nuttx] 01/02: sim/uart: support tty operation in arch/sim

This is an automated email from the ASF dual-hosted git repository.

protobits pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 3634bb6ba5d51f869b38acaecc1c7088211bc4d3
Author: dongjiuzhu <do...@xiaomi.com>
AuthorDate: Mon Aug 31 20:12:32 2020 +0800

    sim/uart: support tty operation in arch/sim
    
    Change-Id: I6943c1e928ed821aa913bc619e5b8c581b5610c3
    Signed-off-by: dongjiuzhu <do...@xiaomi.com>
---
 arch/sim/Kconfig                 |  24 ++
 arch/sim/src/Makefile            |  11 +-
 arch/sim/src/sim/up_devconsole.c | 319 ----------------------
 arch/sim/src/sim/up_idle.c       |   4 +-
 arch/sim/src/sim/up_initialize.c |  10 +-
 arch/sim/src/sim/up_internal.h   |  16 +-
 arch/sim/src/sim/up_simuart.c    | 124 ++++++---
 arch/sim/src/sim/up_uart.c       | 572 +++++++++++++++++++++++++++++++++++++++
 8 files changed, 699 insertions(+), 381 deletions(-)

diff --git a/arch/sim/Kconfig b/arch/sim/Kconfig
index 28f8cf4..a165b45 100644
--- a/arch/sim/Kconfig
+++ b/arch/sim/Kconfig
@@ -485,4 +485,28 @@ config SIM_HCISOCKET
 		control of the device, but is abstracted from the
 		physical interface which is still handled by Linux.
 
+config SIM_UART_NUMBER
+	int "The number of tty ports on sim platform, range is 0~4"
+	default 0
+
+config SIM_UART0_NAME
+	string "the name of uart0 on sim"
+	default "/dev/ttySIM0"
+	depends on SIM_UART_NUMBER >= 1
+
+config SIM_UART1_NAME
+	string "the name of uart1 on sim"
+	default "/dev/ttySIM1"
+	depends on SIM_UART_NUMBER >= 2
+
+config SIM_UART2_NAME
+	string "the name of uart2 on sim"
+	default "/dev/ttySIM2"
+	depends on SIM_UART_NUMBER >= 3
+
+config SIM_UART3_NAME
+	string "the name of uart3 on sim"
+	default "/dev/ttySIM3"
+	depends on SIM_UART_NUMBER >= 4
+
 endif # ARCH_SIM
diff --git a/arch/sim/src/Makefile b/arch/sim/src/Makefile
index a6e58fc..76278e2 100644
--- a/arch/sim/src/Makefile
+++ b/arch/sim/src/Makefile
@@ -73,7 +73,7 @@ CSRCS  = up_initialize.c up_idle.c up_interruptcontext.c up_initialstate.c
 CSRCS += up_createstack.c up_usestack.c up_releasestack.c up_stackframe.c
 CSRCS += up_unblocktask.c up_blocktask.c up_releasepending.c
 CSRCS += up_reprioritizertr.c up_exit.c up_schedulesigaction.c
-CSRCS += up_allocateheap.c
+CSRCS += up_allocateheap.c up_uart.c
 
 VPATH = sim
 DEPPATH = $(patsubst %,--dep-path %,$(subst :, ,$(VPATH)))
@@ -83,7 +83,7 @@ ifeq ($(CONFIG_HOST_MACOS),y)
   HOSTCFLAGS += -Wno-deprecated-declarations
 endif
 
-HOSTSRCS = up_hostirq.c up_hostmemory.c up_hosttime.c
+HOSTSRCS = up_hostirq.c up_hostmemory.c up_hosttime.c up_simuart.c
 STDLIBS += -lpthread
 ifneq ($(CONFIG_HOST_MACOS),y)
   STDLIBS += -lrt
@@ -117,13 +117,6 @@ ifneq ($(CONFIG_SCHED_INSTRUMENTATION_BUFFER),y)
 endif
 endif
 
-ifeq ($(CONFIG_DEV_CONSOLE),y)
-ifneq ($(CONFIG_SYSLOG_RPMSG),y)
-  CSRCS += up_devconsole.c
-  HOSTSRCS += up_simuart.c
-endif
-endif
-
 ifeq ($(CONFIG_ONESHOT),y)
   CSRCS += up_oneshot.c
 endif
diff --git a/arch/sim/src/sim/up_devconsole.c b/arch/sim/src/sim/up_devconsole.c
deleted file mode 100644
index 74fff98..0000000
--- a/arch/sim/src/sim/up_devconsole.c
+++ /dev/null
@@ -1,319 +0,0 @@
-/****************************************************************************
- * arch/sim/src/sim/up_devconsole.c
- *
- *   Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@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 <nuttx/serial/serial.h>
-
-#include "up_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define DEVCONSOLE_BUFSIZE 256
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-static int  devconsole_setup(FAR struct uart_dev_s *dev);
-static void devconsole_shutdown(FAR struct uart_dev_s *dev);
-static int  devconsole_attach(FAR struct uart_dev_s *dev);
-static void devconsole_detach(FAR struct uart_dev_s *dev);
-static int  devconsole_ioctl(FAR struct file *filep, int cmd,
-                             unsigned long arg);
-static int  devconsole_receive(FAR struct uart_dev_s *dev, uint32_t *status);
-static void devconsole_rxint(FAR struct uart_dev_s *dev, bool enable);
-static bool devconsole_rxavailable(FAR struct uart_dev_s *dev);
-static void devconsole_send(FAR struct uart_dev_s *dev, int ch);
-static void devconsole_txint(FAR struct uart_dev_s *dev, bool enable);
-static bool devconsole_txready(FAR struct uart_dev_s *dev);
-static bool devconsole_txempty(FAR struct uart_dev_s *dev);
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static const struct uart_ops_s g_devconsole_ops =
-{
-  .setup          = devconsole_setup,
-  .shutdown       = devconsole_shutdown,
-  .attach         = devconsole_attach,
-  .detach         = devconsole_detach,
-  .ioctl          = devconsole_ioctl,
-  .receive        = devconsole_receive,
-  .rxint          = devconsole_rxint,
-  .rxavailable    = devconsole_rxavailable,
-  .send           = devconsole_send,
-  .txint          = devconsole_txint,
-  .txready        = devconsole_txready,
-  .txempty        = devconsole_txempty,
-};
-
-static char g_devconsole_rxbuf[DEVCONSOLE_BUFSIZE];
-static char g_devconsole_txbuf[DEVCONSOLE_BUFSIZE];
-
-static struct uart_dev_s g_devconsole_dev =
-{
-  .isconsole      = true,
-  .ops            = &g_devconsole_ops,
-  .xmit =
-  {
-    .size         = DEVCONSOLE_BUFSIZE,
-    .buffer       = g_devconsole_txbuf,
-  },
-  .recv =
-  {
-    .size         = DEVCONSOLE_BUFSIZE,
-    .buffer       = g_devconsole_rxbuf,
-  },
-};
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: devconsole_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 devconsole_setup(FAR struct uart_dev_s *dev)
-{
-  return OK;
-}
-
-/****************************************************************************
- * Name: devconsole_shutdown
- *
- * Description:
- *   Disable the UART.  This method is called when the serial
- *   port is closed
- *
- ****************************************************************************/
-
-static void devconsole_shutdown(struct uart_dev_s *dev)
-{
-}
-
-/****************************************************************************
- * Name: devconsole_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 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 devconsole_attach(struct uart_dev_s *dev)
-{
-  return OK;
-}
-
-/****************************************************************************
- * Name: devconsole_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 devconsole_detach(FAR struct uart_dev_s *dev)
-{
-}
-
-/****************************************************************************
- * Name: devconsole_ioctl
- *
- * Description:
- *   All ioctl calls will be routed through this method
- *
- ****************************************************************************/
-
-static int devconsole_ioctl(struct file *filep, int cmd, unsigned long arg)
-{
-  return -ENOTTY;
-}
-
-/****************************************************************************
- * Name: devconsole_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 return 'status'.
- *
- ****************************************************************************/
-
-static int devconsole_receive(struct uart_dev_s *dev, uint32_t *status)
-{
-  *status = 0;
-  return simuart_getc();
-}
-
-/****************************************************************************
- * Name: devconsole_rxint
- *
- * Description:
- *   Call to enable or disable RX interrupts
- *
- ****************************************************************************/
-
-static void devconsole_rxint(struct uart_dev_s *dev, bool enable)
-{
-}
-
-/****************************************************************************
- * Name: devconsole_rxavailable
- *
- * Description:
- *   Return true if the receive fifo is not empty
- *
- ****************************************************************************/
-
-static bool devconsole_rxavailable(struct uart_dev_s *dev)
-{
-  return simuart_checkc();
-}
-
-/****************************************************************************
- * Name: devconsole_send
- *
- * Description:
- *   This method will send one byte on the UART
- *
- ****************************************************************************/
-
-static void devconsole_send(struct uart_dev_s *dev, int ch)
-{
-  simuart_putc(ch);
-}
-
-/****************************************************************************
- * Name: devconsole_txint
- *
- * Description:
- *   Call to enable or disable TX interrupts
- *
- ****************************************************************************/
-
-static void devconsole_txint(struct uart_dev_s *dev, bool enable)
-{
-  if (enable)
-    {
-      uart_xmitchars(&g_devconsole_dev);
-    }
-}
-
-/****************************************************************************
- * Name: devconsole_txready
- *
- * Description:
- *   Return true if the tranmsit fifo is not full
- *
- ****************************************************************************/
-
-static bool devconsole_txready(struct uart_dev_s *dev)
-{
-  return true;
-}
-
-/****************************************************************************
- * Name: devconsole_txempty
- *
- * Description:
- *   Return true if the transmit fifo is empty
- *
- ****************************************************************************/
-
-static bool devconsole_txempty(struct uart_dev_s *dev)
-{
-  return true;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: up_devconsole
- ****************************************************************************/
-
-void up_devconsole(void)
-{
-  uart_register("/dev/console", &g_devconsole_dev);
-  uart_register("/dev/ttyS0", &g_devconsole_dev);
-}
-
-/****************************************************************************
- * Name: up_devconloop
- ****************************************************************************/
-
-void up_devconloop(void)
-{
-  if (simuart_checkc())
-    {
-      uart_recvchars(&g_devconsole_dev);
-    }
-}
-
-/****************************************************************************
- * Name: up_putc
- ****************************************************************************/
-
-int up_putc(int ch)
-{
-  /* Just map to the host simuart_putc routine */
-
-  return simuart_putc(ch);
-}
diff --git a/arch/sim/src/sim/up_idle.c b/arch/sim/src/sim/up_idle.c
index d319b9d..b7fda31 100644
--- a/arch/sim/src/sim/up_idle.c
+++ b/arch/sim/src/sim/up_idle.c
@@ -89,11 +89,9 @@ void up_idle(void)
     }
 #endif
 
-#ifdef USE_DEVCONSOLE
   /* Handle UART data availability */
 
-  up_devconloop();
-#endif
+  up_uartloop();
 
 #if defined(CONFIG_SIM_TOUCHSCREEN) || defined(CONFIG_SIM_AJOYSTICK)
   /* Drive the X11 event loop */
diff --git a/arch/sim/src/sim/up_initialize.c b/arch/sim/src/sim/up_initialize.c
index c226bff..ad253c1 100644
--- a/arch/sim/src/sim/up_initialize.c
+++ b/arch/sim/src/sim/up_initialize.c
@@ -228,15 +228,11 @@ void up_initialize(void)
   rpmsg_serialinit();
 #endif
 
-#if defined(USE_DEVCONSOLE)
-  /* Start the simulated UART device */
+  /* Register some tty-port to access tty-port on sim platform */
 
-  simuart_start();
+  up_uartinit();
 
-  /* Register a console (or not) */
-
-  up_devconsole();          /* Our private /dev/console */
-#elif defined(CONFIG_CONSOLE_SYSLOG)
+#if defined(CONFIG_CONSOLE_SYSLOG)
   syslog_console_init();
 #endif
 
diff --git a/arch/sim/src/sim/up_internal.h b/arch/sim/src/sim/up_internal.h
index df24178..7eb8a1b 100644
--- a/arch/sim/src/sim/up_internal.h
+++ b/arch/sim/src/sim/up_internal.h
@@ -259,17 +259,21 @@ void up_timer_update(void);
 void rpmsg_serialinit(void);
 #endif
 
-/* up_devconsole.c **********************************************************/
+/* up_uart.c ****************************************************************/
 
-void up_devconsole(void);
-void up_devconloop(void);
+void up_uartinit(void);
+void up_uartloop(void);
 
 /* up_simuart.c *************************************************************/
 
 void simuart_start(void);
-int  simuart_putc(int ch);
-int  simuart_getc(void);
-bool simuart_checkc(void);
+int  simuart_open(const char *pathname);
+void simuart_close(int fd);
+int  simuart_putc(int fd, int ch);
+int  simuart_getc(int fd);
+bool simuart_checkc(int fd);
+int  simuart_setcflag(int fd, unsigned int cflag);
+int  simuart_getcflag(int fd, unsigned int *cflag);
 
 /* up_deviceimage.c *********************************************************/
 
diff --git a/arch/sim/src/sim/up_simuart.c b/arch/sim/src/sim/up_simuart.c
index cdb7551..7d89e46 100644
--- a/arch/sim/src/sim/up_simuart.c
+++ b/arch/sim/src/sim/up_simuart.c
@@ -37,12 +37,14 @@
  * Included Files
  ****************************************************************************/
 
+#include <fcntl.h>
 #include <stdbool.h>
 #include <unistd.h>
 #include <string.h>
 #include <stdlib.h>
 #include <termios.h>
 #include <poll.h>
+#include <errno.h>
 
 /****************************************************************************
  * Private Data
@@ -58,18 +60,14 @@ static struct termios g_cooked;
  * Name: setrawmode
  ****************************************************************************/
 
-static void setrawmode(void)
+static void setrawmode(int fd)
 {
   struct termios raw;
 
-  /* Get the current stdin terminal mode */
-
-  tcgetattr(0, &g_cooked);
+  tcgetattr(fd, &raw);
 
   /* Switch to raw mode */
 
-  memcpy(&raw, &g_cooked, sizeof(struct termios));
-
   raw.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR |
                    ICRNL | IXON);
   raw.c_oflag &= ~OPOST;
@@ -77,7 +75,7 @@ static void setrawmode(void)
   raw.c_cflag &= ~(CSIZE | PARENB);
   raw.c_cflag |= CS8;
 
-  tcsetattr(0, TCSANOW, &raw);
+  tcsetattr(fd, TCSANOW, &raw);
 }
 
 /****************************************************************************
@@ -92,85 +90,137 @@ static void restoremode(void)
 }
 
 /****************************************************************************
- * Name: simuart_putraw
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: simuart_start
+ ****************************************************************************/
+
+void simuart_start(void)
+{
+  /* Get the current stdin terminal mode */
+
+  tcgetattr(0, &g_cooked);
+
+  /* Put stdin into raw mode */
+
+  setrawmode(0);
+
+  /* Restore the original terminal mode before exit */
+
+  atexit(restoremode);
+}
+
+/****************************************************************************
+ * Name: simuart_open
  ****************************************************************************/
 
-int simuart_putraw(int ch)
+int simuart_open(const char *pathname)
 {
-  ssize_t nwritten;
-  unsigned char buf = ch;
+  int fd;
 
-  nwritten = write(1, &buf, 1);
-  if (nwritten != 1)
+  fd = open(pathname, O_RDWR | O_NONBLOCK);
+  if (fd >= 0)
     {
-      return -1;
+      /* keep raw mode */
+
+      setrawmode(fd);
+    }
+  else
+    {
+      fd = -errno;
     }
 
-  return ch;
+  return fd;
 }
 
 /****************************************************************************
- * Public Functions
+ * Name: simuart_close
  ****************************************************************************/
 
+void simuart_close(int fd)
+{
+  close(fd);
+}
+
 /****************************************************************************
- * Name: simuart_start
+ * Name: simuart_putc
  ****************************************************************************/
 
-void simuart_start(void)
+int simuart_putc(int fd, int ch)
 {
-  /* Put stdin into raw mode */
+  return write(fd, &ch, 1) == 1 ? ch : -1;
+}
 
-  setrawmode();
+/****************************************************************************
+ * Name: simuart_getc
+ ****************************************************************************/
 
-  /* Restore the original terminal mode before exit */
+int simuart_getc(int fd)
+{
+  int ret;
+  unsigned char ch;
 
-  atexit(restoremode);
+  ret = read(fd, &ch, 1);
+  return ret < 0 ? ret : ch;
 }
 
 /****************************************************************************
- * Name: simuart_putc
+ * Name: simuart_getcflag
  ****************************************************************************/
 
-int simuart_putc(int ch)
+int simuart_getcflag(int fd, tcflag_t *cflag)
 {
-  int ret = ch;
+  struct termios t;
+  int ret;
 
-  if (ch == '\n')
+  ret = tcgetattr(fd, &t);
+  if (ret < 0)
     {
-      ret = simuart_putraw('\r');
+      ret = -errno;
     }
-
-  if (ret >= 0)
+  else
     {
-      ret = simuart_putraw(ch);
+      *cflag = t.c_cflag;
     }
 
   return ret;
 }
 
 /****************************************************************************
- * Name: simuart_getc
+ * Name: simuart_setcflag
  ****************************************************************************/
 
-int simuart_getc(void)
+int simuart_setcflag(int fd, tcflag_t cflag)
 {
+  struct termios t;
   int ret;
-  unsigned char ch;
 
-  ret = read(0, &ch, 1);
-  return ret < 0 ? ret : ch;
+  ret = tcgetattr(fd, &t);
+  if (!ret)
+    {
+      t.c_cflag = cflag;
+      ret = tcsetattr(fd, TCSANOW, &t);
+    }
+
+  if (ret < 0)
+    {
+      ret = -errno;
+    }
+
+  return ret;
 }
 
 /****************************************************************************
  * Name: simuart_checkc
  ****************************************************************************/
 
-bool simuart_checkc(void)
+bool simuart_checkc(int fd)
 {
   struct pollfd pfd;
 
-  pfd.fd     = 0;
+  pfd.fd     = fd;
   pfd.events = POLLIN;
   return poll(&pfd, 1, 0) == 1;
 }
diff --git a/arch/sim/src/sim/up_uart.c b/arch/sim/src/sim/up_uart.c
new file mode 100644
index 0000000..5d08cb5
--- /dev/null
+++ b/arch/sim/src/sim/up_uart.c
@@ -0,0 +1,572 @@
+/****************************************************************************
+ * arch/sim/src/sim/up_uart.c
+ *
+ *   Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved.
+ *   Author: Gregory Nutt <gn...@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 <nuttx/serial/serial.h>
+#include <nuttx/fs/ioctl.h>
+#include <sys/types.h>
+#include <fcntl.h>
+#include <errno.h>
+
+#include "up_internal.h"
+
+#if defined(USE_DEVCONSOLE) || CONFIG_SIM_UART_NUMBER > 0
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define BUFSIZE 256
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct tty_priv_s
+{
+  /* tty-port path name */
+
+  FAR const char *path;
+
+  /* The file descriptor. It is returned by open */
+
+  int             fd;
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int  tty_setup(FAR struct uart_dev_s *dev);
+static void tty_shutdown(FAR struct uart_dev_s *dev);
+static int  tty_attach(FAR struct uart_dev_s *dev);
+static void tty_detach(FAR struct uart_dev_s *dev);
+static int  tty_ioctl(FAR struct file *filep, int cmd,
+                      unsigned long arg);
+static int  tty_receive(FAR struct uart_dev_s *dev, uint32_t *status);
+static void tty_rxint(FAR struct uart_dev_s *dev, bool enable);
+static bool tty_rxavailable(FAR struct uart_dev_s *dev);
+static void tty_send(FAR struct uart_dev_s *dev, int ch);
+static void tty_txint(FAR struct uart_dev_s *dev, bool enable);
+static bool tty_txready(FAR struct uart_dev_s *dev);
+static bool tty_txempty(FAR struct uart_dev_s *dev);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const struct uart_ops_s g_tty_ops =
+{
+  .setup          = tty_setup,
+  .shutdown       = tty_shutdown,
+  .attach         = tty_attach,
+  .detach         = tty_detach,
+  .ioctl          = tty_ioctl,
+  .receive        = tty_receive,
+  .rxint          = tty_rxint,
+  .rxavailable    = tty_rxavailable,
+  .send           = tty_send,
+  .txint          = tty_txint,
+  .txready        = tty_txready,
+  .txempty        = tty_txempty,
+};
+#endif
+
+#ifdef USE_DEVCONSOLE
+static char g_console_rxbuf[BUFSIZE];
+static char g_console_txbuf[BUFSIZE];
+#endif
+
+#ifdef CONFIG_SIM_UART0_NAME
+static char g_tty0_rxbuf[BUFSIZE];
+static char g_tty0_txbuf[BUFSIZE];
+#endif
+
+#ifdef CONFIG_SIM_UART1_NAME
+static char g_tty1_rxbuf[BUFSIZE];
+static char g_tty1_txbuf[BUFSIZE];
+#endif
+
+#ifdef CONFIG_SIM_UART2_NAME
+static char g_tty2_rxbuf[BUFSIZE];
+static char g_tty2_txbuf[BUFSIZE];
+#endif
+
+#ifdef CONFIG_SIM_UART3_NAME
+static char g_tty3_rxbuf[BUFSIZE];
+static char g_tty3_txbuf[BUFSIZE];
+#endif
+
+#ifdef USE_DEVCONSOLE
+static struct uart_dev_s g_console_dev =
+{
+  .isconsole      = true,
+  .ops            = &g_tty_ops,
+  .xmit =
+  {
+    .size         = BUFSIZE,
+    .buffer       = g_console_txbuf,
+  },
+  .recv =
+  {
+    .size         = BUFSIZE,
+    .buffer       = g_console_rxbuf,
+  },
+};
+#endif
+
+#ifdef CONFIG_SIM_UART0_NAME
+static struct tty_priv_s g_tty0_priv =
+{
+  .path           = CONFIG_SIM_UART0_NAME,
+  .fd             = -1,
+};
+
+static struct uart_dev_s g_tty0_dev =
+{
+  .ops            = &g_tty_ops,
+  .priv           = &g_tty0_priv,
+  .xmit =
+  {
+    .size         = BUFSIZE,
+    .buffer       = g_tty0_txbuf,
+  },
+  .recv =
+  {
+    .size         = BUFSIZE,
+    .buffer       = g_tty0_rxbuf,
+  },
+};
+#endif
+
+#ifdef CONFIG_SIM_UART1_NAME
+static struct tty_priv_s g_tty1_priv =
+{
+  .path           = CONFIG_SIM_UART1_NAME,
+  .fd             = -1,
+};
+
+static struct uart_dev_s g_tty1_dev =
+{
+  .ops            = &g_tty_ops,
+  .priv           = &g_tty1_priv,
+  .xmit =
+  {
+    .size         = BUFSIZE,
+    .buffer       = g_tty1_txbuf,
+  },
+  .recv =
+  {
+    .size         = BUFSIZE,
+    .buffer       = g_tty1_rxbuf,
+  },
+};
+#endif
+
+#ifdef CONFIG_SIM_UART2_NAME
+static struct tty_priv_s g_tty2_priv =
+{
+  .path           = CONFIG_SIM_UART2_NAME,
+  .fd             = -1,
+};
+
+static struct uart_dev_s g_tty2_dev =
+{
+  .ops            = &g_tty_ops,
+  .priv           = &g_tty2_priv,
+  .xmit =
+  {
+    .size         = BUFSIZE,
+    .buffer       = g_tty2_txbuf,
+  },
+  .recv =
+  {
+    .size         = BUFSIZE,
+    .buffer       = g_tty2_rxbuf,
+  },
+};
+#endif
+
+#ifdef CONFIG_SIM_UART3_NAME
+static struct tty_priv_s g_tty3_priv =
+{
+  .path           = CONFIG_SIM_UART3_NAME,
+  .fd             = -1,
+};
+
+static struct uart_dev_s g_tty3_dev =
+{
+  .ops            = &g_tty_ops,
+  .priv           = &g_tty3_priv,
+  .xmit =
+  {
+    .size         = BUFSIZE,
+    .buffer       = g_tty3_txbuf,
+  },
+  .recv =
+  {
+    .size         = BUFSIZE,
+    .buffer       = g_tty3_rxbuf,
+  },
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+#if defined(USE_DEVCONSOLE) || CONFIG_SIM_UART_NUMBER > 0
+/****************************************************************************
+ * Name: tty_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 tty_setup(FAR struct uart_dev_s *dev)
+{
+  FAR struct tty_priv_s *priv = dev->priv;
+
+  if (!dev->isconsole && priv->fd < 0)
+    {
+      priv->fd = simuart_open(priv->path);
+      if (priv->fd < 0)
+        {
+          return priv->fd;
+        }
+    }
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: tty_shutdown
+ *
+ * Description:
+ *   Disable the UART.  This method is called when the serial
+ *   port is closed
+ *
+ ****************************************************************************/
+
+static void tty_shutdown(struct uart_dev_s *dev)
+{
+  FAR struct tty_priv_s *priv = dev->priv;
+
+  if (!dev->isconsole && priv->fd >= 0)
+    {
+      /* close file Description and reset fd */
+
+      simuart_close(priv->fd);
+      priv->fd = -1;
+    }
+}
+
+/****************************************************************************
+ * Name: tty_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 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 tty_attach(struct uart_dev_s *dev)
+{
+  return OK;
+}
+
+/****************************************************************************
+ * Name: tty_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 tty_detach(FAR struct uart_dev_s *dev)
+{
+}
+
+/****************************************************************************
+ * Name: tty_ioctl
+ *
+ * Description:
+ *   All ioctl calls will be routed through this method
+ *
+ ****************************************************************************/
+
+static int tty_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+#ifdef CONFIG_SERIAL_TERMIOS
+  FAR struct inode *inode = filep->f_inode;
+  FAR struct uart_dev_s *dev = inode->i_private;
+  FAR struct tty_priv_s *priv = dev->priv;
+  FAR struct termios *termiosp = (FAR struct termios *)(uintptr_t)arg;
+
+  if (!termiosp)
+    {
+      return -EINVAL;
+    }
+
+  switch (cmd)
+    {
+      case TCGETS:
+        return simuart_getcflag(dev->isconsole ? 0 : priv->fd,
+                                &termiosp->c_cflag);
+
+      case TCSETS:
+        return simuart_setcflag(dev->isconsole ? 0 : priv->fd,
+                               termiosp->c_cflag);
+    }
+#endif
+
+  return -ENOTTY;
+}
+
+/****************************************************************************
+ * Name: tty_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 return 'status'.
+ *
+ ****************************************************************************/
+
+static int tty_receive(struct uart_dev_s *dev, uint32_t *status)
+{
+  FAR struct tty_priv_s *priv = dev->priv;
+
+  *status = 0;
+  return simuart_getc(dev->isconsole ? 0 : priv->fd);
+}
+
+/****************************************************************************
+ * Name: tty_rxint
+ *
+ * Description:
+ *   Call to enable or disable RX interrupts
+ *
+ ****************************************************************************/
+
+static void tty_rxint(struct uart_dev_s *dev, bool enable)
+{
+}
+
+/****************************************************************************
+ * Name: tty_rxavailable
+ *
+ * Description:
+ *   Return true if the receive fifo is not empty
+ *
+ ****************************************************************************/
+
+static bool tty_rxavailable(struct uart_dev_s *dev)
+{
+  FAR struct tty_priv_s *priv = dev->priv;
+
+  return simuart_checkc(dev->isconsole ? 0 : priv->fd);
+}
+
+/****************************************************************************
+ * Name: tty_send
+ *
+ * Description:
+ *   This method will send one byte on the UART
+ *
+ ****************************************************************************/
+
+static void tty_send(struct uart_dev_s *dev, int ch)
+{
+  FAR struct tty_priv_s *priv = dev->priv;
+
+  /* For console device */
+
+  if (dev->isconsole && ch == '\n')
+    {
+      simuart_putc(1, '\r');
+    }
+
+  simuart_putc(dev->isconsole ? 1 : priv->fd, ch);
+}
+
+/****************************************************************************
+ * Name: tty_txint
+ *
+ * Description:
+ *   Call to enable or disable TX interrupts
+ *
+ ****************************************************************************/
+
+static void tty_txint(struct uart_dev_s *dev, bool enable)
+{
+  if (enable)
+    {
+      uart_xmitchars(dev);
+    }
+}
+
+/****************************************************************************
+ * Name: uart_txready
+ *
+ * Description:
+ *   Return true if the tranmsit fifo is not full
+ *
+ ****************************************************************************/
+
+static bool tty_txready(struct uart_dev_s *dev)
+{
+  return true;
+}
+
+/****************************************************************************
+ * Name: tty_txempty
+ *
+ * Description:
+ *   Return true if the transmit fifo is empty
+ *
+ ****************************************************************************/
+
+static bool tty_txempty(struct uart_dev_s *dev)
+{
+  return true;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_uart
+ ****************************************************************************/
+
+void up_uartinit(void)
+{
+#ifdef USE_DEVCONSOLE
+  /* Start the simulated UART device */
+
+  simuart_start();
+
+  /* Register console device */
+
+  uart_register("/dev/console", &g_console_dev);
+#endif
+
+#ifdef CONFIG_SIM_UART0_NAME
+  uart_register(CONFIG_SIM_UART0_NAME, &g_tty0_dev);
+#endif
+
+#ifdef CONFIG_SIM_UART1_NAME
+  uart_register(CONFIG_SIM_UART1_NAME, &g_tty1_dev);
+#endif
+
+#ifdef CONFIG_SIM_UART2_NAME
+  uart_register(CONFIG_SIM_UART2_NAME, &g_tty2_dev);
+#endif
+
+#ifdef CONFIG_SIM_UART3_NAME
+  uart_register(CONFIG_SIM_UART3_NAME, &g_tty3_dev);
+#endif
+}
+
+/****************************************************************************
+ * Name: up_uartloop
+ ****************************************************************************/
+
+void up_uartloop(void)
+{
+#ifdef USE_DEVCONSOLE
+  if (simuart_checkc(0))
+    {
+      uart_recvchars(&g_console_dev);
+    }
+#endif
+
+#ifdef CONFIG_SIM_UART0_NAME
+  if (g_tty0_priv.fd > 0 && simuart_checkc(g_tty0_priv.fd))
+    {
+      uart_recvchars(&g_tty0_dev);
+    }
+#endif
+
+#ifdef CONFIG_SIM_UART1_NAME
+  if (g_tty1_priv.fd > 0 && simuart_checkc(g_tty1_priv.fd))
+    {
+      uart_recvchars(&g_tty1_dev);
+    }
+#endif
+
+#ifdef CONFIG_SIM_UART2_NAME
+  if (g_tty2_priv.fd > 0 && simuart_checkc(g_tty2_priv.fd))
+    {
+      uart_recvchars(&g_tty2_dev);
+    }
+#endif
+
+#ifdef CONFIG_SIM_UART3_NAME
+  if (g_tty3_priv.fd > 0 && simuart_checkc(g_tty3_priv.fd))
+    {
+      uart_recvchars(&g_tty3_dev);
+    }
+#endif
+}
+
+/****************************************************************************
+ * Name: up_putc
+ ****************************************************************************/
+
+#ifdef USE_DEVCONSOLE
+int up_putc(int ch)
+{
+  tty_send(&g_console_dev, ch);
+  return 0;
+}
+#endif