summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog1
-rw-r--r--nuttx/Documentation/NuttX.html1
-rw-r--r--nuttx/TODO6
-rw-r--r--nuttx/arch/z16/src/common/up_initialize.c6
-rw-r--r--nuttx/arch/z16/src/common/up_internal.h20
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_head.S14
-rwxr-xr-xnuttx/arch/z16/src/z16f/z16f_lowuart.S6
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_serial.c30
-rw-r--r--nuttx/configs/z16f2800100zcog/ostest/defconfig1
-rw-r--r--nuttx/drivers/Makefile2
-rwxr-xr-xnuttx/drivers/lowconsole.c124
-rw-r--r--nuttx/drivers/serial.c8
12 files changed, 197 insertions, 22 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index ad99a0baa..c812bf773 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -306,3 +306,4 @@
* Add support for Windows native toolchains that cannot follow Cygwin soft links
* Modified serial driver interface to handle hardware with non-16550A-like
interrupt architecture (like the Z16F)
+ * Added a "dumb" serial console driver to simply OS bringup
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 38bea91aa..2c7d6531a 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -984,6 +984,7 @@ Other memory:
* Add support for Windows native toolchains that cannot follow Cygwin soft links
* Modified serial driver interface to handle hardware with non-16550A-like
interrupt architecture (like the Z16F)
+ * Added a "dumb" serial console driver to simply OS bringup
</pre></ul>
<table width ="100%">
diff --git a/nuttx/TODO b/nuttx/TODO
index e5a4b51d1..8029936d1 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -21,7 +21,7 @@ NuttX TODO List (Last updated January 6, 2008)
(2) ARM/LPC214x (arch/arm/src/lpc214x/)
(4) pjrc-8052 / MCS51 (arch/pjrc-8051/)
(2) z80 (arch/z80/)
- (2) z16 (arch/z16/)
+ (3) z16 (arch/z16/)
o Task/Scheduler (sched/)
^^^^^^^^^^^^^^^^^^^^^^^
@@ -382,3 +382,7 @@ o z16 (arch/z16)
Status: Open
Priority: Medium. A polled, write-only serial driver is used in the
interim for system testing.
+
+ Description: Signals are not functional
+ Status: Open
+ Priority: Medium
diff --git a/nuttx/arch/z16/src/common/up_initialize.c b/nuttx/arch/z16/src/common/up_initialize.c
index 8a30d33ad..b7fc643d2 100644
--- a/nuttx/arch/z16/src/common/up_initialize.c
+++ b/nuttx/arch/z16/src/common/up_initialize.c
@@ -160,7 +160,13 @@ void up_initialize(void)
/* Initialize the serial device driver */
+#ifdef CONFIG_USE_SERIALDRIVER
up_serialinit();
+#endif
+
+#ifdef CONFIG_USE_LOWCONSOLE
+ lowconsole_init();
+#endif
/* Initialize the netwok */
diff --git a/nuttx/arch/z16/src/common/up_internal.h b/nuttx/arch/z16/src/common/up_internal.h
index f6acb97a6..144fee754 100644
--- a/nuttx/arch/z16/src/common/up_internal.h
+++ b/nuttx/arch/z16/src/common/up_internal.h
@@ -58,6 +58,17 @@
#undef CONFIG_SUPPRESS_UART_CONFIG /* Do not reconfig UART */
#undef CONFIG_DUMP_ON_EXIT /* Dump task state on exit */
+/* Determine which (if any) console driver to use */
+
+#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC) || \
+ CONFIG_NFILE_DESCRIPTORS == 0 || defined(CONFIG_DEV_LOWCONSOLE)
+# define CONFIG_USE_LOWCONSOLE 1
+# define CONFIG_USE_LOWUARTINIT 1
+#elif defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0
+# define CONFIG_USE_SERIALDRIVER 1
+# define CONFIG_USE_EARLYSERIALINIT 1
+#endif
+
/* Macros for portability */
#define IN_INTERRUPT (current_regs != NULL)
@@ -118,12 +129,13 @@ void up_addregion(void);
/* Defined in up_serial.c */
-#if CONFIG_NFILE_DESCRIPTORS > 0
+#ifdef CONFIG_USE_SERIALDRIVER
extern void up_earlyserialinit(void);
extern void up_serialinit(void);
-#else
-# define up_earlyserialinit()
-# define up_serialinit()
+#endif
+
+#ifdef CONFIG_USE_LOWCONSOLE
+extern void lowconsole_init(void);
#endif
/* Defined in up_timerisr.c */
diff --git a/nuttx/arch/z16/src/z16f/z16f_head.S b/nuttx/arch/z16/src/z16f/z16f_head.S
index f6108c250..88b9ca5bb 100755
--- a/nuttx/arch/z16/src/z16f/z16f_head.S
+++ b/nuttx/arch/z16/src/z16f/z16f_head.S
@@ -40,6 +40,11 @@
#include <nuttx/config.h>
#include <arch/irq.h>
+#include "common/up_internal.h"
+
+/**************************************************************************
+ * Definitions
+ **************************************************************************/
/**************************************************************************
* External References / External Definitions
@@ -50,10 +55,9 @@
#ifdef CONFIG_ARCH_LEDS
xref _up_ledinit:EROM
#endif
-#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC) || CONFIG_NFILE_DESCRIPTORS == 0
+#if defined(CONFIG_USE_LOWUARTINIT)
xref _z16f_lowuartinit:EROM
-#endif
-#if defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0
+#elif defined(CONFIG_USE_EARLYSERIALINIT)
xref _up_earlyserialinit:EROM
#endif
xref _os_start:EROM
@@ -157,7 +161,7 @@ _z16f_reset:
#endif
/* Perform VERY early UART initialization so that we can use it here */
-#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC) || CONFIG_NFILE_DESCRIPTORS == 0
+#ifdef CONFIG_USE_LOWUARTINIT
call _z16f_lowuartinit /* Initialize the UART for debugging */
#endif
/* Initialize the hardware stack overflow register */
@@ -210,7 +214,7 @@ _z16f_reset8:
call _z16f_lowinit /* Perform low-level hardware initialization */
-#if defined(CONFIG_DEV_CONSOLE) && CONFIG_NFILE_DESCRIPTORS > 0
+#ifdef CONFIG_USE_EARLYSERIALINIT
/* Perform early serial initialization */
call _up_earlyserialinit
diff --git a/nuttx/arch/z16/src/z16f/z16f_lowuart.S b/nuttx/arch/z16/src/z16f/z16f_lowuart.S
index bea5f25fc..1dedf16b3 100755
--- a/nuttx/arch/z16/src/z16f/z16f_lowuart.S
+++ b/nuttx/arch/z16/src/z16f/z16f_lowuart.S
@@ -40,8 +40,9 @@
#include <nuttx/config.h>
#include "chip/chip.h"
+#include "common/up_internal.h"
-#if defined(CONFIG_ARCH_LOWPUTC) || defined(CONFIG_ARCH_LOWGETC) || CONFIG_NFILE_DESCRIPTORS == 0
+#ifdef CONFIG_USE_LOWUARTINIT
/*************************************************************************
* External References / External Definitions
@@ -120,6 +121,7 @@ _z16f_lowuartinit:
ld.b Z16F_UART0_CTL0, r0 /* Z16F_UART0_CTL0 = %c0 */
#endif
ret /* Return */
+#endif /* CONFIG_USE_LOWUARTINIT */
/*************************************************************************
* Name: _up_lowputc
@@ -222,7 +224,5 @@ _up_lowgetc3: /* Return value in r0 */
ret /* Return */
#endif
-#endif /* CONFIG_ARCH_LOWPUTC || CONFIG_ARCH_LOWGETC */
-
end
diff --git a/nuttx/arch/z16/src/z16f/z16f_serial.c b/nuttx/arch/z16/src/z16f/z16f_serial.c
index ce40a497f..1446c5c57 100644
--- a/nuttx/arch/z16/src/z16f/z16f_serial.c
+++ b/nuttx/arch/z16/src/z16f/z16f_serial.c
@@ -55,14 +55,12 @@
#include "os_internal.h"
#include "up_internal.h"
-#if CONFIG_NFILE_DESCRIPTORS > 0
+#ifdef CONFIG_USE_SERIALDRIVER
/****************************************************************************
* Definitions
****************************************************************************/
-#define BASE_BAUD 115200
-
/* System clock frequency value from ZDS target settings */
extern _Erom unsigned long SYS_CLK_FREQ;
@@ -737,7 +735,7 @@ int up_putc(int ch)
return ch;
}
-#else /* CONFIG_NFILE_DESCRIPTORS > 0 */
+#else /* CONFIG_USE_SERIALDRIVER */
/****************************************************************************
* Definitions
@@ -756,10 +754,22 @@ int up_putc(int ch)
#endif
/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
* Private Functions
****************************************************************************/
-static void _up_putc(int ch)
+/****************************************************************************
+ * Name: z16f_putc
+ ****************************************************************************/
+
+static void z16f_putc(int ch)
{
int tmp;
for (tmp = 1000 ; tmp > 0 && !z16f_contrde(); tmp--);
@@ -770,6 +780,10 @@ static void _up_putc(int ch)
* Public Functions
****************************************************************************/
+/****************************************************************************
+ * Name: up_putc
+ ****************************************************************************/
+
int up_putc(int ch)
{
/* Check for LF */
@@ -778,13 +792,13 @@ int up_putc(int ch)
{
/* Output CR before LF */
- _up_putc('\r');
+ z16f_putc('\r');
}
/* Output character */
- _up_putc(ch);
+ z16f_putc(ch);
return ch;
}
-#endif /* CONFIG_NFILE_DESCRIPTORS > 0 */
+#endif /* CONFIG_USE_SERIALDRIVER */
diff --git a/nuttx/configs/z16f2800100zcog/ostest/defconfig b/nuttx/configs/z16f2800100zcog/ostest/defconfig
index eb24435af..4e95b886a 100644
--- a/nuttx/configs/z16f2800100zcog/ostest/defconfig
+++ b/nuttx/configs/z16f2800100zcog/ostest/defconfig
@@ -152,6 +152,7 @@ CONFIG_START_MONTH=1
CONFIG_START_DAY=28
CONFIG_JULIAN_TIME=n
CONFIG_DEV_CONSOLE=y
+CONFIG_DEV_LOWCONSOLE=y
#
# The following can be used to disable categories of
diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile
index 1655629d7..d105e75ea 100644
--- a/nuttx/drivers/Makefile
+++ b/nuttx/drivers/Makefile
@@ -44,7 +44,7 @@ AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS =
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
-CSRCS += dev_null.c serial.c
+CSRCS += dev_null.c serial.c lowconsole.c
endif
CSRCS += $(NET_CSRCS)
COBJS = $(CSRCS:.c=$(OBJEXT))
diff --git a/nuttx/drivers/lowconsole.c b/nuttx/drivers/lowconsole.c
new file mode 100755
index 000000000..743f09a0a
--- /dev/null
+++ b/nuttx/drivers/lowconsole.c
@@ -0,0 +1,124 @@
+/****************************************************************************
+ * drivers/lowconsole.c
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/fs.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static ssize_t lowconsole_read(struct file *filep, char *buffer, size_t buflen);
+static ssize_t lowconsole_write(struct file *filep, const char *buffer, size_t buflen);
+static int lowconsole_ioctl(struct file *filep, int cmd, unsigned long arg);
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+struct file_operations g_serialops =
+{
+ 0, /* open */
+ 0, /* close */
+ lowconsole_read, /* read */
+ lowconsole_write, /* write */
+ 0, /* seek */
+ lowconsole_ioctl /* ioctl */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: lowconsole_ioctl
+ ****************************************************************************/
+
+static int lowconsole_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+ *get_errno_ptr() = ENOTTY;
+ return ERROR;
+}
+
+/****************************************************************************
+ * Name: lowconsole_read
+ ****************************************************************************/
+
+static ssize_t lowconsole_read(struct file *filep, char *buffer, size_t buflen)
+{
+ return 0;
+}
+
+/****************************************************************************
+ * Name: lowconsole_write
+ ****************************************************************************/
+
+static ssize_t lowconsole_write(struct file *filep, const char *buffer, size_t buflen)
+{
+ ssize_t ret = buflen;
+
+ for (; buflen; buflen--)
+ {
+ up_putc(*buffer++);
+ }
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: lowconsole_init
+****************************************************************************/
+
+void lowconsole_init(void)
+{
+ (void)register_driver("/dev/console", &g_serialops, 0666, NULL);
+}
diff --git a/nuttx/drivers/serial.c b/nuttx/drivers/serial.c
index 153ee431d..2f0f5703f 100644
--- a/nuttx/drivers/serial.c
+++ b/nuttx/drivers/serial.c
@@ -344,14 +344,22 @@ static int uart_close(struct file *filep)
while (dev->xmit.head != dev->xmit.tail)
{
+#ifndef CONFIG_DISABLE_SIGNALS
usleep(500*1000);
+#else
+ up_udelay(500*1000);
+#endif
}
/* And wait for the TX fifo to drain */
while (!uart_txempty(dev))
{
+#ifndef CONFIG_DISABLE_SIGNALS
usleep(500*1000);
+#else
+ up_udelay(500*1000);
+#endif
}
/* Free the IRQ and disable the UART */