summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c8
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/Make.defs7
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S1
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_serial.c176
-rwxr-xr-xnuttx/configs/demo9s12ne64/README.txt21
-rwxr-xr-xnuttx/configs/demo9s12ne64/ostest/defconfig87
-rw-r--r--nuttx/configs/z80sim/ostest/defconfig5
7 files changed, 253 insertions, 52 deletions
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index a702b1b5c..c94f08b03 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -939,12 +939,12 @@ static boolean up_txready(struct uart_dev_s *dev)
****************************************************************************/
/****************************************************************************
- * Name: up_serialinit
+ * Name: up_earlyserialinit
*
* Description:
- * Performs the low level USART initialization early in
- * debug so that the serial console will be available
- * during bootup. This must be called before up_serialinit.
+ * Performs the low level USART initialization early in debug so that the
+ * serial console will be available during bootup. This must be called
+ * before up_serialinit.
*
****************************************************************************/
diff --git a/nuttx/arch/hc/src/mc9s12ne64/Make.defs b/nuttx/arch/hc/src/mc9s12ne64/Make.defs
index 330ecc442..46330eb5b 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/Make.defs
+++ b/nuttx/arch/hc/src/mc9s12ne64/Make.defs
@@ -36,7 +36,10 @@
HEAD_ASRC = mc9s12ne64_vectors.S
CMN_ASRCS =
-CMN_CSRCS =
+CMN_CSRCS = up_allocateheap.c up_createstack.c up_idle.c up_initialize.c \
+ up_interruptcontext.c up_mdelay.c up_modifyreg16.c \
+ up_modifyreg32.c up_modifyreg8.c up_puts.c up_releasestack.c \
+ up_udelay.c up_usestack.c
CHIP_ASRCS = mc9s12ne64_start.S mc9s12ne64_lowputc.S
-CHIP_CSRCS =
+CHIP_CSRCS = mc9s12ne64_serial.c
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S
index aaa0d4089..3a42f2de0 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S
@@ -98,6 +98,7 @@ up_lowputc:
jmp PutChar
#else
# error "up_lowputc not implemented"
+ rts
#endif
.size up_lowputc, . - up_lowputc
.end
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_serial.c b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_serial.c
new file mode 100755
index 000000000..1cfa4ab88
--- /dev/null
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_serial.c
@@ -0,0 +1,176 @@
+/****************************************************************************
+ * arch/hc/src/mc9s12ne64/mc9s12ne64_serial.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Some sanity checks *******************************************************/
+
+/* Is there an SCI enabled? */
+
+#if !defined(CONFIG_HCS12_SCI0) && !defined(CONFIG_HCS12_SCI1)
+# undef HAVE_SERIAL
+#else
+# define HAVE_SERIAL 1
+#endif
+
+/* Is there a serial console? Need to have (1) at least SCI enabled, and (2)
+ * serial console and file descriptors selected in the configuration
+ */
+
+#if defined(HAVE_SERIAL) && defined(CONFIG_USE_SERIALDRIVER)
+# if defined(CONFIG_SCI0_SERIAL_CONSOLE) && defined(CONFIG_HCS12_SCI0)
+# undef CONFIG_SCI1_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+# elif defined(CONFIG_SCI1_SERIAL_CONSOLE) && defined(CONFIG_HCS12_SCI1)
+# undef CONFIG_SCI0_SERIAL_CONSOLE
+# define HAVE_SERIAL_CONSOLE 1
+# else
+# undef CONFIG_SCI0_SERIAL_CONSOLE
+# undef CONFIG_SCI1_SERIAL_CONSOLE
+# undef HAVE_SERIAL_CONSOLE
+# endif
+#else
+# undef CONFIG_SCI0_SERIAL_CONSOLE
+# undef CONFIG_SCI1_SERIAL_CONSOLE
+# undef HAVE_SERIAL_CONSOLE
+# undef CONFIG_USE_SERIALDRIVER
+# undef CONFIG_USE_EARLYSERIALINIT
+#endif
+
+#ifdef CONFIG_USE_SERIALDRIVER
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_earlyserialinit
+ *
+ * Description:
+ * Performs the low level SCI initialization early in debug so that the
+ * serial console will be available during bootup. This must be called
+ * before up_serialinit.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_USE_EARLYSERIALINIT
+void up_earlyserialinit(void)
+{
+#error "Serial support not-implemented"
+}
+#endif
+
+/****************************************************************************
+ * Name: up_serialinit
+ *
+ * Description:
+ * Register serial console and serial ports. This assumes
+ * that up_earlyserialinit was called previously.
+ *
+ ****************************************************************************/
+
+void up_serialinit(void)
+{
+#error "Serial support not-implemented"
+}
+
+/****************************************************************************
+ * Name: up_putc
+ *
+ * Description:
+ * Provide priority, low-level access to support OS debug writes
+ *
+ ****************************************************************************/
+
+int up_putc(int ch)
+{
+#error "Serial support not-implemented"
+}
+
+#else /* CONFIG_USE_SERIALDRIVER */
+
+/****************************************************************************
+ * Name: up_putc
+ *
+ * Description:
+ * Provide priority, low-level access to support OS debug writes
+ *
+ ****************************************************************************/
+
+int up_putc(int ch)
+{
+#ifdef CONFIG_ARCH_LOWPUTC
+ /* Check for LF */
+
+ if (ch == '\n')
+ {
+ /* Add CR */
+
+ up_lowputc('\r');
+ }
+
+ up_lowputc(ch);
+#endif
+ return ch;
+}
+
+#endif /* CONFIG_USE_SERIALDRIVER */
diff --git a/nuttx/configs/demo9s12ne64/README.txt b/nuttx/configs/demo9s12ne64/README.txt
index 0aceb49fc..ef063b784 100755
--- a/nuttx/configs/demo9s12ne64/README.txt
+++ b/nuttx/configs/demo9s12ne64/README.txt
@@ -264,24 +264,29 @@ HCS12/DEMO9S12NEC64-specific Configuration Options
in this configuration: pages 3e, 3d, then 3f will appear as a
contiguous address space in memory.
+ HCS12 Sub-system support
+
+ CONFIG_HCS12_SCI0
+ CONFIG_HCS12_SCI1
+
HCS12 specific device driver settings:
- CONFIG_SCIO_SERIAL_CONSOLE - selects the SCIO for the
- console and ttys0 (default is the UART0).
+ CONFIG_SCIn_SERIAL_CONSOLE - selects SCIn for the console and ttys0
+ (default is the SCI0).
- CONFIG_SCIO_RXBUFSIZE - Characters are buffered as received.
+ CONFIG_SCIn_RXBUFSIZE - Characters are buffered as received.
This specific the size of the receive buffer
- CONFIG_SCIO_TXBUFSIZE - Characters are buffered before
+ CONFIG_SCIn_TXBUFSIZE - Characters are buffered before
being sent. This specific the size of the transmit buffer
- CONFIG_SCIO_BAUD - The configure BAUD of the UART.
+ CONFIG_SCIn_BAUD - The configure BAUD of the UART.
- CONFIG_SCIO_BITS - The number of bits. Must be either 7 or 8.
+ CONFIG_SCIn_BITS - The number of bits. Must be either 7 or 8.
- CONFIG_SCIO_PARTIY - 0=no parity, 1=odd parity, 2=even parity, 3=mark 1, 4=space 0
+ CONFIG_SCIn_PARTIY - 0=no parity, 1=odd parity, 2=even parity, 3=mark 1, 4=space 0
- CONFIG_SCIO_2STOP - Two stop bits
+ CONFIG_SCIn_2STOP - Two stop bits
Configurations
^^^^^^^^^^^^^^
diff --git a/nuttx/configs/demo9s12ne64/ostest/defconfig b/nuttx/configs/demo9s12ne64/ostest/defconfig
index 82fa012a3..9366f5321 100755
--- a/nuttx/configs/demo9s12ne64/ostest/defconfig
+++ b/nuttx/configs/demo9s12ne64/ostest/defconfig
@@ -33,7 +33,7 @@
#
############################################################################
#
-# architecture selection
+# Architecture selection
#
# CONFIG_ARCH - identifies the arch subdirectory and, hence, the
# processor architecture.
@@ -80,10 +80,10 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=0x00010000
CONFIG_DRAM_START=0x20000000
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
-CONFIG_ARCH_IRQPRIO=y
+CONFIG_ARCH_IRQPRIO=n
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
-CONFIG_ARCH_BOOTLOADER=n
+CONFIG_ARCH_BOOTLOADER=y
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
@@ -105,26 +105,40 @@ CONFIG_HCS12_SERIALMON=y
CONFIG_HCS12_NONBANKED=y
#
+# CS12 Sub-system support
+#
+CONFIG_HCS12_SCI0=n
+CONFIG_HCS12_SCI1=n
+
+#
# MC9S12NEC64 specific serial device driver settings
#
-# CONFIG_SCIO_SERIAL_CONSOLE - selects the SCIO for the
-# console and ttys0 (default is the SCIO).
-# CONFIG_SCIO_RXBUFSIZE - Characters are buffered as received.
+# CONFIG_SCIn_SERIAL_CONSOLE - selects SCIn for the
+# console and ttys0 (default is the SCIn).
+# CONFIG_SCIn_RXBUFSIZE - Characters are buffered as received.
# This specific the size of the receive buffer
-# CONFIG_SCIO_TXBUFSIZE - Characters are buffered before
+# CONFIG_SCIn_TXBUFSIZE - Characters are buffered before
# being sent. This specific the size of the transmit buffer
-# CONFIG_SCIO_BAUD - The configure BAUD of the UART. Must be
-# CONFIG_SCIO_BITS - The number of bits. Must be either 7 or 8.
-# CONFIG_SCIO_PARTIY - 0=no parity, 1=odd parity, 2=even parity
-# CONFIG_SCIO_2STOP - Two stop bits
-#
-CONFIG_SCIO_SERIAL_CONSOLE=y
-CONFIG_SCIO_TXBUFSIZE=32
-CONFIG_SCIO_RXBUFSIZE=32
-CONFIG_SCIO_BAUD=115200
-CONFIG_SCIO_BITS=8
-CONFIG_SCIO_PARITY=0
-CONFIG_SCIO_2STOP=0
+# CONFIG_SCIn_BAUD - The configure BAUD of the UART. Must be
+# CONFIG_SCIn_BITS - The number of bits. Must be either 7 or 8.
+# CONFIG_SCIn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+# CONFIG_SCIn_2STOP - Two stop bits
+#
+CONFIG_SCI0_SERIAL_CONSOLE=n
+CONFIG_SCI0_TXBUFSIZE=32
+CONFIG_SCI0_RXBUFSIZE=32
+CONFIG_SCI0_BAUD=115200
+CONFIG_SCI0_BITS=8
+CONFIG_SCI0_PARITY=0
+CONFIG_SCI0_2STOP=0
+
+CONFIG_SCI1_SERIAL_CONSOLE=n
+CONFIG_SCI1_TXBUFSIZE=32
+CONFIG_SCI1_RXBUFSIZE=32
+CONFIG_SCI1_BAUD=115200
+CONFIG_SCI1_BITS=8
+CONFIG_SCI1_PARITY=0
+CONFIG_SCI1_2STOP=0
#
# MC9S12NEC64 specific SSI device driver settings
@@ -272,8 +286,8 @@ CONFIG_START_MONTH=12
CONFIG_START_DAY=11
CONFIG_GREGORIAN_TIME=n
CONFIG_JULIAN_TIME=n
-CONFIG_DEV_CONSOLE=y
-CONFIG_DEV_LOWCONSOLE=y
+CONFIG_DEV_CONSOLE=n
+CONFIG_DEV_LOWCONSOLE=n
CONFIG_MUTEX_TYPES=n
CONFIG_PRIORITY_INHERITANCE=n
CONFIG_SEM_PREALLOCHOLDERS=0
@@ -303,11 +317,11 @@ CONFIG_SIG_SIGWORK=4
# o pthread_condtimedwait() depends on signals to wake
# up waiting tasks.
#
-CONFIG_DISABLE_CLOCK=n
-CONFIG_DISABLE_POSIX_TIMERS=n
-CONFIG_DISABLE_PTHREAD=n
-CONFIG_DISABLE_SIGNALS=n
-CONFIG_DISABLE_MQUEUE=n
+CONFIG_DISABLE_CLOCK=y
+CONFIG_DISABLE_POSIX_TIMERS=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_DISABLE_SIGNALS=y
+CONFIG_DISABLE_MQUEUE=y
CONFIG_DISABLE_MOUNTPOINT=y
CONFIG_DISABLE_ENVIRON=y
CONFIG_DISABLE_POLL=y
@@ -318,7 +332,7 @@ CONFIG_DISABLE_POLL=y
# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
# little smaller if we do not support fieldwidthes
#
-CONFIG_NOPRINTF_FIELDWIDTH=n
+CONFIG_NOPRINTF_FIELDWIDTH=y
#
# Allow for architecture optimized implementations
@@ -374,19 +388,19 @@ CONFIG_ARCH_KFREE=n
# timer structures to minimize dynamic allocations. Set to
# zero for all dynamic allocations.
#
-CONFIG_MAX_TASKS=16
+CONFIG_MAX_TASKS=8
CONFIG_MAX_TASK_ARGS=4
-CONFIG_NPTHREAD_KEYS=4
-CONFIG_NFILE_DESCRIPTORS=8
-CONFIG_NFILE_STREAMS=8
+CONFIG_NPTHREAD_KEYS=0
+CONFIG_NFILE_DESCRIPTORS=0
+CONFIG_NFILE_STREAMS=0
CONFIG_NAME_MAX=32
-CONFIG_STDIO_BUFFER_SIZE=256
-CONFIG_NUNGET_CHARS=2
-CONFIG_PREALLOC_MQ_MSGS=4
-CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_STDIO_BUFFER_SIZE=0
+CONFIG_NUNGET_CHARS=0
+CONFIG_PREALLOC_MQ_MSGS=0
+CONFIG_MQ_MAXMSGSIZE=0
CONFIG_MAX_WDOGPARMS=2
CONFIG_PREALLOC_WDOGS=4
-CONFIG_PREALLOC_TIMERS=4
+CONFIG_PREALLOC_TIMERS=0
#
# Filesystem configuration
@@ -394,6 +408,7 @@ CONFIG_PREALLOC_TIMERS=4
# CONFIG_FS_FAT - Enable FAT filesystem support
# CONFIG_FAT_SECTORSIZE - Max supported sector size
# CONFIG_FS_ROMFS - Enable ROMFS filesystem support
+#
CONFIG_FS_FAT=n
CONFIG_FS_ROMFS=n
diff --git a/nuttx/configs/z80sim/ostest/defconfig b/nuttx/configs/z80sim/ostest/defconfig
index 0e48ca1dc..301fa4e4c 100644
--- a/nuttx/configs/z80sim/ostest/defconfig
+++ b/nuttx/configs/z80sim/ostest/defconfig
@@ -210,7 +210,7 @@ CONFIG_NOPRINTF_FIELDWIDTH=y
# Allow for architecture optimized implementations
#
# The architecture can provide optimized versions of the
-# following to improve sysem performance
+# following to improve system performance
#
CONFIG_ARCH_MEMCPY=n
CONFIG_ARCH_MEMCMP=n
@@ -229,7 +229,7 @@ CONFIG_ARCH_KFREE=n
# Sizes of configurable things (0 disables)
#
# CONFIG_MAX_TASKS - The maximum number of simultaneously
-# actived tasks. This value must be a power of two.
+# active tasks. This value must be a power of two.
# CONFIG_MAX_TASK_ARGS - This controls the maximum number of
# of parameters that a task may receive (i.e., maxmum value
# of 'argc')
@@ -300,6 +300,7 @@ CONFIG_PREALLOC_TIMERS=0
# CONFIG_NET_BROADCAST - Broadcast support
# CONFIG_NET_LLH_LEN - The link level header length
# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates
+#
CONFIG_NET=n
CONFIG_NET_IPv6=n
CONFIG_NSOCKET_DESCRIPTORS=0