summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-11 15:29:11 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-11 15:29:11 +0000
commitd8ac0a01d815d109e177b6f752806f8512c4319e (patch)
tree0565d059f83e489f56f0b08bd02cd3eb311ca56d /nuttx/arch
parent6ba662ab23d592662476229148b230f4f01df197 (diff)
downloadpx4-nuttx-d8ac0a01d815d109e177b6f752806f8512c4319e.tar.gz
px4-nuttx-d8ac0a01d815d109e177b6f752806f8512c4319e.tar.bz2
px4-nuttx-d8ac0a01d815d109e177b6f752806f8512c4319e.zip
Fixes for serial monitor
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2320 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rwxr-xr-xnuttx/arch/hc/include/hc12/limits.h6
-rwxr-xr-xnuttx/arch/hc/include/hcs12/irq.h112
-rwxr-xr-xnuttx/arch/hc/include/hcs12/limits.h86
-rwxr-xr-xnuttx/arch/hc/include/hcs12/types.h96
-rwxr-xr-xnuttx/arch/hc/include/irq.h4
-rwxr-xr-xnuttx/arch/hc/include/limits.h4
-rwxr-xr-xnuttx/arch/hc/include/mc9s12ne64/irq.h92
-rwxr-xr-xnuttx/arch/hc/include/types.h4
-rwxr-xr-xnuttx/arch/hc/src/Makefile3
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/Make.defs2
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/chip.h2
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h48
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_internal.h145
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S103
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h18
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S53
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_vectors.S88
17 files changed, 716 insertions, 150 deletions
diff --git a/nuttx/arch/hc/include/hc12/limits.h b/nuttx/arch/hc/include/hc12/limits.h
index 3d4206e2a..8d4d5f843 100755
--- a/nuttx/arch/hc/include/hc12/limits.h
+++ b/nuttx/arch/hc/include/hc12/limits.h
@@ -59,11 +59,11 @@
#define USHRT_MAX 0xffff
/* The size of an integer is controlled with the -mshort or -mnoshort GCC
- * options. Here we assume that -mshort is applied and that the size of
- * and integer is 2-bytes (unless CONFIG_HC12_INT32 is defined)
+ * options. GCC will set the pre-defined symbol __INT__ to indicate the size
+ * of an integer
*/
-#ifdef CONFIG_HC12_INT32
+#if __INT__ == 32
# define INT_MIN 0x80000000
# define INT_MAX 0x7fffffff
# define UINT_MAX 0xffffffff
diff --git a/nuttx/arch/hc/include/hcs12/irq.h b/nuttx/arch/hc/include/hcs12/irq.h
new file mode 100755
index 000000000..6e2e45ee0
--- /dev/null
+++ b/nuttx/arch/hc/include/hcs12/irq.h
@@ -0,0 +1,112 @@
+/************************************************************************************
+ * arch/hc/include/hcs12/irq.h
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+/* This file should never be included directed but, rather,
+ * only indirectly through nuttx/irq.h
+ */
+
+#ifndef __ARCH_HC_INCLUDE_HCS12_IRQ_H
+#define __ARCH_HC_INCLUDE_HCS12_IRQ_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <nuttx/irq.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/* This structure defines the way the registers are stored. */
+
+#ifndef __ASSEMBLY__
+struct xcptcontext
+{
+ int dummy; /* For now */
+};
+
+/****************************************************************************
+ * Inline functions
+ ****************************************************************************/
+
+/* Save the current interrupt enable state & disable IRQs */
+
+static inline irqstate_t irqsave(void)
+{
+ /* To be provided */
+}
+
+/* Restore saved IRQ & FIQ state */
+
+static inline void irqrestore(irqstate_t flags)
+{
+ /* To be provided */
+}
+
+static inline void system_call(swint_t func, int parm1,
+ int parm2, int parm3)
+{
+ /* To be provided */
+}
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_HC_INCLUDE_HCS12_IRQ_H */
diff --git a/nuttx/arch/hc/include/hcs12/limits.h b/nuttx/arch/hc/include/hcs12/limits.h
new file mode 100755
index 000000000..d9ebaa94a
--- /dev/null
+++ b/nuttx/arch/hc/include/hcs12/limits.h
@@ -0,0 +1,86 @@
+/****************************************************************************
+ * arch/hc/include/hcs12/limits.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_HC_INCLUDE_HCS12_LIMITS_H
+#define __ARCH_HC_INCLUDE_HCS12_LIMITS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+#define CHAR_BIT 8
+#define SCHAR_MIN 0x80
+#define SCHAR_MAX 0x7f
+#define UCHAR_MAX 0xff
+
+/* These could be different on machines where char is unsigned */
+
+#define CHAR_MIN SCHAR_MIN
+#define CHAR_MAX SCHAR_MAX
+
+#define SHRT_MIN 0x8000
+#define SHRT_MAX 0x7fff
+#define USHRT_MAX 0xffff
+
+/* The size of an integer is controlled with the -mshort or -mnoshort GCC
+ * options. GCC will set the pre-defined symbol __INT__ to indicate the size
+ * of an integer
+ */
+
+#if __INT__ == 32
+# define INT_MIN 0x80000000
+# define INT_MAX 0x7fffffff
+# define UINT_MAX 0xffffffff
+#else
+# define INT_MIN 0x8000
+# define INT_MAX 0x7fff
+# define UINT_MAX 0xffff
+#endif
+
+/* Long is 4-bytes and long long is 8 bytes in any case */
+
+#define LONG_MAX 0x80000000
+#define LONG_MIN 0x7fffffff
+#define ULONG_MAX 0xffffffff
+
+#define LLONG_MAX 0x8000000000000000
+#define LLONG_MIN 0x7fffffffffffffff
+#define ULLONG_MAX 0xffffffffffffffff
+
+#endif /* __ARCH_HC_INCLUDE_HCS12_LIMITS_H */
diff --git a/nuttx/arch/hc/include/hcs12/types.h b/nuttx/arch/hc/include/hcs12/types.h
new file mode 100755
index 000000000..1341377e4
--- /dev/null
+++ b/nuttx/arch/hc/include/hcs12/types.h
@@ -0,0 +1,96 @@
+/****************************************************************************
+ * arch/hc/include/hcs12/types.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/* This file should never be included directed but, rather, only indirectly
+ * through sys/types.h
+ */
+
+#ifndef __ARCH_HC_INCLUDE_HCS12_TYPES_H
+#define __ARCH_HC_INCLUDE_HCS12_TYPES_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Declarations
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/* These are the sizes of the standard GNU types */
+
+typedef char sbyte;
+typedef unsigned char ubyte;
+typedef unsigned char uint8;
+typedef unsigned char boolean;
+typedef short sint16;
+typedef unsigned short uint16;
+
+/* Normally, mc68hc1x code is compiled with the -mshort option
+ * which results in a 16-bit integer. If -mnoshort is defined
+ * then an integer is 32-bits. GCC will defined __INT__ accordingly:
+ */
+
+# if __INT__ == 16
+typedef long sint32;
+typedef unsigned long uint32;
+#else
+typedef int sint32;
+typedef unsigned int uint32;
+#endif
+
+typedef long long sint64;
+typedef unsigned long long uint64;
+
+/* A pointer is two bytes */
+
+typedef unsigned short uintptr;
+
+/* This is the size of the interrupt state save returned by irqsave()*/
+
+typedef unsigned int irqstate_t;
+
+#endif /* __ASSEMBLY__ */
+
+/****************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ARCH_HC_INCLUDE_HCS12_TYPES_H */
diff --git a/nuttx/arch/hc/include/irq.h b/nuttx/arch/hc/include/irq.h
index a649ee9d4..fbf7a624e 100755
--- a/nuttx/arch/hc/include/irq.h
+++ b/nuttx/arch/hc/include/irq.h
@@ -56,8 +56,10 @@
* save structure and irqsave()/irqrestore() macros
*/
-#ifdef CONFIG_ARCH_HC12
+#if defined(CONFIG_ARCH_HC12)
# include <arch/hc12/irq.h>
+#elif defined(CONFIG_ARCH_HCS12)
+# include <arch/hcs12/irq.h>
#endif
/****************************************************************************
diff --git a/nuttx/arch/hc/include/limits.h b/nuttx/arch/hc/include/limits.h
index fb74bf1b3..5a2c9791e 100755
--- a/nuttx/arch/hc/include/limits.h
+++ b/nuttx/arch/hc/include/limits.h
@@ -42,8 +42,10 @@
/* Include architecture-specific limits definitions */
-#ifdef CONFIG_ARCH_HC12
+#if defined(CONFIG_ARCH_HC12)
# include <arch/hc12/limits.h>
+#elif defined(CONFIG_ARCH_HCS12)
+# include <arch/hcs12/limits.h>
#endif
/****************************************************************************
diff --git a/nuttx/arch/hc/include/mc9s12ne64/irq.h b/nuttx/arch/hc/include/mc9s12ne64/irq.h
index ed13dafcc..dc98f3b8c 100755
--- a/nuttx/arch/hc/include/mc9s12ne64/irq.h
+++ b/nuttx/arch/hc/include/mc9s12ne64/irq.h
@@ -54,52 +54,52 @@
/* IRQ Numbers */
-#define HC12_IRQ_VRESET 0 /* fffe: External reset, power on reset orlow voltage reset */
-#define HC12_IRQ_VCLKMON 1 /* fffc: Clock monitor fail reset */
-#define HC12_IRQ_VCOP 2 /* fffa: COP failure reset*/
-#define HC12_IRQ_VTRAP 3 /* fff8: Unimplemented instruction trap */
-#define HC12_IRQ_VSWI 4 /* fff6: SWI */
-#define HC12_IRQ_VXIRQ 5 /* fff4: XIRQ */
-#define HC12_IRQ_VIRQ 6 /* fff2: IRQ */
-#define HC12_IRQ_VRTI 7 /* fff0: Real-time interrupt */
- /* ffe8-ffef: Reserved */
-#define HC12_IRQ_VTIMCH4 8 /* ffe6: Standard timer channel 4 */
-#define HC12_IRQ_VTIMCH5 9 /* ffe4: Standard timer channel 5 */
-#define HC12_IRQ_VTIMCH6 10 /* ffe2: Standard timer channel 6 */
-#define HC12_IRQ_VTIMCH7 11 /* ffe0: Standard timer channel 7 */
-#define HC12_IRQ_VTIMOVF 12 /* ffde: Standard timer overflow */
-#define HC12_IRQ_VTIMPAOVF 13 /* ffdc: Pulse accumulator overflow */
-#define HC12_IRQ_VTIMPAIE 14 /* ffda: Pulse accumulator input edge */
-#define HC12_IRQ_VSPI 15 /* ffd8: SPI */
-#define HC12_IRQ_VSCI0 16 /* ffd6: SCI0 */
-#define HC12_IRQ_VSCI1 17 /* ffd4: SCI1 */
-#define HC12_IRQ_VATD 18 /* ffd2: ATD */
- /* ffd0: Reserved */
-#define HC12_IRQ_VPORTJ 19 /* ffce: Port J */
-#define HC12_IRQ_VPORTH 20 /* ffcc: Port H */
-#define HC12_IRQ_VPORTG 21 /* ffca: Port G */
- /* ffc8: Reserved */
-#define HC12_IRQ_VCRGPLLLCK 22 /* ffc6: CRG PLL lock */
-#define HC12_IRQ_VCRGSCM 23 /* ffc4: CRG self clock mode */
- /* ffc2: Reserved */
-#define HC12_IRQ_VIIC 24 /* ffc0: IIC bus */
- /* ffba-ffbf: Reserved */
-#define HC12_IRQ_VFLASH 25 /* ffb8: FLASH */
-#define HC12_IRQ_VEPHY 26 /* ffb6: EPHY interrupt */
-#define HC12_IRQ_VEMACCRXBAC 27 /* ffb4: EMAC receive buffer A complete */
-#define HC12_IRQ_VEMACCRXBBC 28 /* ffb2: EMAC receive buffer B complete */
-#define HC12_IRQ_VEMACTXC 29 /* ffb0: EMAC frame transmission complete */
-#define HC12_IRQ_VEMACRXFC 30 /* ffae: EMAC receive flow control */
-#define HC12_IRQ_VEMACMII 31 /* ffac: EMAC MII management transfer complete */
-#define HC12_IRQ_VEMACRXERR 32 /* ffaa: EMAC receive error */
-#define HC12_IRQ_VEMACRXBAO 33 /* ffa8: EMAC receive buffer A overrun */
-#define HC12_IRQ_VEMACRXBBO 34 /* ffa6: EMAC receive buffer B overrun */
-#define HC12_IRQ_VEMACBRXERR 35 /* ffa4: EMAC babbling receive error */
-#define HC12_IRQ_VEMACLC 36 /* ffa2: EMAC late collision */
-#define HC12_IRQ_VEMACEC 37 /* ffa0: EMAC excessive collision */
- /* ff80-ff9f: Reserved */
-#define HC12_IRQ_VILLEGAL 38 /* Any reserved vector */
-#define NR_IRQS 39
+#define HCS12_IRQ_VRESET 0 /* fffe: External reset, power on reset orlow voltage reset */
+#define HCS12_IRQ_VCLKMON 1 /* fffc: Clock monitor fail reset */
+#define HCS12_IRQ_VCOP 2 /* fffa: COP failure reset*/
+#define HCS12_IRQ_VTRAP 3 /* fff8: Unimplemented instruction trap */
+#define HCS12_IRQ_VSWI 4 /* fff6: SWI */
+#define HCS12_IRQ_VXIRQ 5 /* fff4: XIRQ */
+#define HCS12_IRQ_VIRQ 6 /* fff2: IRQ */
+#define HCS12_IRQ_VRTI 7 /* fff0: Real-time interrupt */
+ /* ffe8-ffef: Reserved */
+#define HCS12_IRQ_VTIMCH4 8 /* ffe6: Standard timer channel 4 */
+#define HCS12_IRQ_VTIMCH5 9 /* ffe4: Standard timer channel 5 */
+#define HCS12_IRQ_VTIMCH6 10 /* ffe2: Standard timer channel 6 */
+#define HCS12_IRQ_VTIMCH7 11 /* ffe0: Standard timer channel 7 */
+#define HCS12_IRQ_VTIMOVF 12 /* ffde: Standard timer overflow */
+#define HCS12_IRQ_VTIMPAOVF 13 /* ffdc: Pulse accumulator overflow */
+#define HCS12_IRQ_VTIMPAIE 14 /* ffda: Pulse accumulator input edge */
+#define HCS12_IRQ_VSPI 15 /* ffd8: SPI */
+#define HCS12_IRQ_VSCI0 16 /* ffd6: SCI0 */
+#define HCS12_IRQ_VSCI1 17 /* ffd4: SCI1 */
+#define HCS12_IRQ_VATD 18 /* ffd2: ATD */
+ /* ffd0: Reserved */
+#define HCS12_IRQ_VPORTJ 19 /* ffce: Port J */
+#define HCS12_IRQ_VPORTH 20 /* ffcc: Port H */
+#define HCS12_IRQ_VPORTG 21 /* ffca: Port G */
+ /* ffc8: Reserved */
+#define HCS12_IRQ_VCRGPLLLCK 22 /* ffc6: CRG PLL lock */
+#define HCS12_IRQ_VCRGSCM 23 /* ffc4: CRG self clock mode */
+ /* ffc2: Reserved */
+#define HCS12_IRQ_VIIC 24 /* ffc0: IIC bus */
+ /* ffba-ffbf: Reserved */
+#define HCS12_IRQ_VFLASH 25 /* ffb8: FLASH */
+#define HCS12_IRQ_VEPHY 26 /* ffb6: EPHY interrupt */
+#define HCS12_IRQ_VEMACCRXBAC 27 /* ffb4: EMAC receive buffer A complete */
+#define HCS12_IRQ_VEMACCRXBBC 28 /* ffb2: EMAC receive buffer B complete */
+#define HCS12_IRQ_VEMACTXC 29 /* ffb0: EMAC frame transmission complete */
+#define HCS12_IRQ_VEMACRXFC 30 /* ffae: EMAC receive flow control */
+#define HCS12_IRQ_VEMACMII 31 /* ffac: EMAC MII management transfer complete */
+#define HCS12_IRQ_VEMACRXERR 32 /* ffaa: EMAC receive error */
+#define HCS12_IRQ_VEMACRXBAO 33 /* ffa8: EMAC receive buffer A overrun */
+#define HCS12_IRQ_VEMACRXBBO 34 /* ffa6: EMAC receive buffer B overrun */
+#define HCS12_IRQ_VEMACBRXERR 35 /* ffa4: EMAC babbling receive error */
+#define HCS12_IRQ_VEMACLC 36 /* ffa2: EMAC late collision */
+#define HCS12_IRQ_VEMACEC 37 /* ffa0: EMAC excessive collision */
+ /* ff80-ff9f: Reserved */
+#define HCS12_IRQ_VILLEGAL 38 /* Any reserved vector */
+#define NR_IRQS 39
/************************************************************************************
* Public Types
diff --git a/nuttx/arch/hc/include/types.h b/nuttx/arch/hc/include/types.h
index 938d7fc52..5cba37a9f 100755
--- a/nuttx/arch/hc/include/types.h
+++ b/nuttx/arch/hc/include/types.h
@@ -50,8 +50,10 @@
/* Include architecture-specific limits definitions */
-#ifdef CONFIG_ARCH_HC12
+#if defined(CONFIG_ARCH_HC12)
# include <arch/hc12/types.h>
+#elif defined(CONFIG_ARCH_HCS12)
+# include <arch/hcs12/types.h>
#endif
/****************************************************************************
diff --git a/nuttx/arch/hc/src/Makefile b/nuttx/arch/hc/src/Makefile
index 27816b730..694c15d4c 100755
--- a/nuttx/arch/hc/src/Makefile
+++ b/nuttx/arch/hc/src/Makefile
@@ -40,6 +40,9 @@ ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
ifeq ($(CONFIG_ARCH_HC12),y)
ARCH_SUBDIR = hc12
endif
+ifeq ($(CONFIG_ARCH_HCS12),y)
+ARCH_SUBDIR = hcs12
+endif
ifeq ($(WINTOOL),y)
NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}"
diff --git a/nuttx/arch/hc/src/mc9s12ne64/Make.defs b/nuttx/arch/hc/src/mc9s12ne64/Make.defs
index 7bcad4a9b..330ecc442 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/Make.defs
+++ b/nuttx/arch/hc/src/mc9s12ne64/Make.defs
@@ -38,5 +38,5 @@ HEAD_ASRC = mc9s12ne64_vectors.S
CMN_ASRCS =
CMN_CSRCS =
-CHIP_ASRCS = mc9s12ne64_start.S
+CHIP_ASRCS = mc9s12ne64_start.S mc9s12ne64_lowputc.S
CHIP_CSRCS =
diff --git a/nuttx/arch/hc/src/mc9s12ne64/chip.h b/nuttx/arch/hc/src/mc9s12ne64/chip.h
index 0f9afce84..f8f8b0e21 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/chip.h
+++ b/nuttx/arch/hc/src/mc9s12ne64/chip.h
@@ -47,7 +47,7 @@
* Definitions
************************************************************************************/
-#define HC12_MODULE_BASE 0x0000\
+#define HCS12_MODULE_BASE 0x0000
/************************************************************************************
* Public Types
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h
index 40e3b82fe..3731621fb 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h
@@ -50,33 +50,33 @@
/* CRG Module Register Offsets */
-#define HC12_CRG_SYNR_OFFSET 0x34 /* CRG Synthesizer Register */
-#define HC12_CRG_REFDV_OFFSET 0x35 /* CRG Reference Divider Register */
-#define HC12_CRG_CTFLG_OFFSET 0x36 /* CRG Test Flags Register */
-#define HC12_CRG_CRGFLG_OFFSET 0x37 /* CRG Flags Register */
-#define HC12_CRG_CRGINT_OFFSET 0x38 /* CRG Interrupt Enable Register */
-#define HC12_CRG_CLKSEL_OFFSET 0x39 /* CRG Clock Select Register */
-#define HC12_CRG_PLLCTL_OFFSET 0x3a /* CRG PLL Control Register */
-#define HC12_CRG_RTICTL_OFFSET 0x3b /* CRG RTI Control Register */
-#define HC12_CRG_COPCTL_OFFSET 0x3c /* CRG COP Control Register */
-#define HC12_CRG_FORBYP_OFFSET 0x3d /* CRG Force and Bypass Test Register */
-#define HC12_CRG_CTCTL_OFFSET 0x3e /* CRG Test Control Register */
-#define HC12_CRG_ARMCOP_OFFSET 0x3f /* CRG COP Arm/Timer Reset */
+#define HCS12_CRG_SYNR_OFFSET 0x34 /* CRG Synthesizer Register */
+#define HCS12_CRG_REFDV_OFFSET 0x35 /* CRG Reference Divider Register */
+#define HCS12_CRG_CTFLG_OFFSET 0x36 /* CRG Test Flags Register */
+#define HCS12_CRG_CRGFLG_OFFSET 0x37 /* CRG Flags Register */
+#define HCS12_CRG_CRGINT_OFFSET 0x38 /* CRG Interrupt Enable Register */
+#define HCS12_CRG_CLKSEL_OFFSET 0x39 /* CRG Clock Select Register */
+#define HCS12_CRG_PLLCTL_OFFSET 0x3a /* CRG PLL Control Register */
+#define HCS12_CRG_RTICTL_OFFSET 0x3b /* CRG RTI Control Register */
+#define HCS12_CRG_COPCTL_OFFSET 0x3c /* CRG COP Control Register */
+#define HCS12_CRG_FORBYP_OFFSET 0x3d /* CRG Force and Bypass Test Register */
+#define HCS12_CRG_CTCTL_OFFSET 0x3e /* CRG Test Control Register */
+#define HCS12_CRG_ARMCOP_OFFSET 0x3f /* CRG COP Arm/Timer Reset */
/* CRG Module Register Addresses */
-#define HC12_CRG_SYNR (HC12_MODULE_BASE+HC12_CRG_SYNR_OFFSET)
-#define HC12_CRG_REFDV (HC12_MODULE_BASE+HC12_CRG_REFDV_OFFSET)
-#define HC12_CRG_CTFLG (HC12_MODULE_BASE+HC12_CRG_CTFLG_OFFSET)
-#define HC12_CRG_CRGFLG (HC12_MODULE_BASE+HC12_CRG_CRGFLG_OFFSET)
-#define HC12_CRG_CRGINT (HC12_MODULE_BASE+HC12_CRG_CRGINT_OFFSET)
-#define HC12_CRG_CLKSEL (HC12_MODULE_BASE+HC12_CRG_CLKSEL_OFFSET)
-#define HC12_CRG_PLLCTL (HC12_MODULE_BASE+HC12_CRG_PLLCTL_OFFSET)
-#define HC12_CRG_RTICTL (HC12_MODULE_BASE+HC12_CRG_RTICTL_OFFSET)
-#define HC12_CRG_COPCTL (HC12_MODULE_BASE+HC12_CRG_COPCTL_OFFSET)
-#define HC12_CRG_FORBYP (HC12_MODULE_BASE+HC12_CRG_FORBYP_OFFSET)
-#define HC12_CRG_CTCTL (HC12_MODULE_BASE+HC12_CRG_CTCTL_OFFSET)
-#define HC12_CRG_ARMCOP (HC12_MODULE_BASE+HC12_CRG_ARMCOP_OFFSET)
+#define HCS12_CRG_SYNR (HCS12_MODULE_BASE+HCS12_CRG_SYNR_OFFSET)
+#define HCS12_CRG_REFDV (HCS12_MODULE_BASE+HCS12_CRG_REFDV_OFFSET)
+#define HCS12_CRG_CTFLG (HCS12_MODULE_BASE+HCS12_CRG_CTFLG_OFFSET)
+#define HCS12_CRG_CRGFLG (HCS12_MODULE_BASE+HCS12_CRG_CRGFLG_OFFSET)
+#define HCS12_CRG_CRGINT (HCS12_MODULE_BASE+HCS12_CRG_CRGINT_OFFSET)
+#define HCS12_CRG_CLKSEL (HCS12_MODULE_BASE+HCS12_CRG_CLKSEL_OFFSET)
+#define HCS12_CRG_PLLCTL (HCS12_MODULE_BASE+HCS12_CRG_PLLCTL_OFFSET)
+#define HCS12_CRG_RTICTL (HCS12_MODULE_BASE+HCS12_CRG_RTICTL_OFFSET)
+#define HCS12_CRG_COPCTL (HCS12_MODULE_BASE+HCS12_CRG_COPCTL_OFFSET)
+#define HCS12_CRG_FORBYP (HCS12_MODULE_BASE+HCS12_CRG_FORBYP_OFFSET)
+#define HCS12_CRG_CTCTL (HCS12_MODULE_BASE+HCS12_CRG_CTCTL_OFFSET)
+#define HCS12_CRG_ARMCOP (HCS12_MODULE_BASE+HCS12_CRG_ARMCOP_OFFSET)
/* CRG Module Register Bit Definitions */
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_internal.h b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_internal.h
new file mode 100755
index 000000000..1db25a19b
--- /dev/null
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_internal.h
@@ -0,0 +1,145 @@
+/************************************************************************************
+ * arch/hc/src/mc9s12ne64/mc9x12ne64_internal.h
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_HC_SRC_MC9S12NE64_MC9S12NE64_INTERNAL_H
+#define __ARCH_HC_SRC_MC9S12NE64_MC9S12NE64_INTERNAL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+#include "up_internal.h"
+#include "chip.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Configuration ********************************************************************/
+
+/* User-Accessible utility subroutines provided by the serial monitor */
+
+#define PutChar 0xfee6 /* Sends the character in A out SCI0 */
+#define GetChar 0xfee9 /* Return character received from SCIO in A */
+#define EraseAllCmd 0xfeec /* Erase all flash (except bootloader) */
+#define DoOnStack 0xfeef /* Copy to stack and execute from RAM */
+#define WriteD2IX 0xfef2 /* Write the data in D (word) to the address in IX.
+ * The location may be RAM, FLASH, EEPROM, or a register */
+
+/************************************************************************************
+ * 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
+ ************************************************************************************/
+
+/************************************************************************************
+ * Function: hcs12_ethinitialize
+ *
+ * Description:
+ * Initialize the Ethernet driver for one interface. If the STM32 chip
+ * supports multiple Ethernet controllers, then bould specific logic
+ * must implement up_netinitialize() and call this function to initialize
+ * the desiresed interfaces.
+ *
+ * Parameters:
+ * None
+ *
+ * Returned Value:
+ * OK on success; Negated errno on failure.
+ *
+ * Assumptions:
+ *
+ ************************************************************************************/
+
+#if STM32_NTHERNET > 1
+EXTERN int hcs12_ethinitialize(int intf);
+#endif
+
+/************************************************************************************
+ * Name: hcs12_spiselect and hcs12_spistatus
+ *
+ * Description:
+ * The external functions, hcs12_spiselect and hcs12_spistatus must be
+ * provided by board-specific logic. They are implementations of the select
+ * and status methods of the SPI interface defined by struct spi_ops_s (see
+ * include/nuttx/spi.h). All other methods (including up_spiinitialize())
+ * are provided by common STM32 logic. To use this common SPI logic on your
+ * board:
+ *
+ * 1. Provide logic in hcs12_boardinitialize() to configure SPI chip select
+ * pins.
+ * 2. Provide hcs12_spiselect() and hcs12_spistatus() functions in your
+ * board-specific logic. These functions will perform chip selection and
+ * status operations using GPIOs in the way your board is configured.
+ * 3. Add a calls to up_spiinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by up_spiinitialize() may then be used to bind the
+ * SPI driver to higher level logic (e.g., calling
+ * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
+ * the SPI MMC/SD driver).
+ *
+ ************************************************************************************/
+
+struct spi_dev_s;
+enum spi_dev_e;
+EXTERN void hcs12_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, boolean selected);
+EXTERN ubyte hcs12_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_HC_SRC_MC9S12NE64_MC9S12NE64_INTERNAL_H */
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S
new file mode 100755
index 000000000..05777546c
--- /dev/null
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S
@@ -0,0 +1,103 @@
+/**************************************************************************
+ * arch/arm/src/mc9s12ne64/mc9s12ne64_lowputc.S
+ *
+ * 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 "up_internal.h"
+
+#include "up_arch.h"
+#include "mc9s12ne64_internal.h"
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Function Prototypes
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_lowsetup
+ **************************************************************************/
+
+ .text
+ .globl up_lowsetup
+ .type up_lowsetup, function
+up_lowsetup:
+#ifdef CONFIG_HCS12_SERIALMON
+ rts
+#else
+# error "up_lowsetup not implemented"
+#endif
+ .size up_lowsetup, . - up_lowsetup
+
+/**************************************************************************
+ * Name: up_lowputc
+ **************************************************************************/
+
+ .text
+ .global up_lowputc
+ .type up_lowputc, function
+up_lowputc:
+#ifdef CONFIG_HCS12_SERIALMON
+ bra PutChar
+#else
+# error "up_lowputc not implemented"
+#endif
+ .size up_lowputc, . - up_lowputc
+ .end
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h
index 12d4f7b17..11ecc2636 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h
@@ -50,21 +50,21 @@
/* MMC Sub-block */
-#define HC12_MMC_INITRM 0x0010 /* Internal RAM Position Register */
+#define HCS12_MMC_INITRM 0x0010 /* Internal RAM Position Register */
# define MMC_INITRM_RAMHAL (1 << 0) /* Bit 0: RAM High-Align */
# define MMC_INITRM_RAM_SHIFT (3) /* Bits 3-7: Internal RAM Map Position */
# define MMC_INITRM_RAM_MASK (0x1f << MMC_INITRM_RAM_SHIFT)
-#define HC12_MMC_INITRG 0x0011 /* Internal Registers Position Register */
+#define HCS12_MMC_INITRG 0x0011 /* Internal Registers Position Register */
# define MMC_INITRG_REG_SHIFT (3) /* Bits 3-6: Internal RAM Map Position */
# define MMC_INITRG_REG_MASK (0x0f << MMC_INITRG_REG_SHIFT)
-#define HC12_MMC_INITEE 0x0012 /* Internal EEPROM Position Register */
+#define HCS12_MMC_INITEE 0x0012 /* Internal EEPROM Position Register */
# define MMC_INITEE_EEON (1 << 0) /* Bit 0: Enable EEPROM */
# define MMC_INITEE_EE_SHIFT (3) /* Bits 3-7: Internal EEPROM Map Position */
# define MMC_INITEE_EE_MASK (0x1f << MMC_INITEE_EE_SHIFT)
-#define HC12_MMC_MISC 0x0013 /* Miscellaneous System Control Register */
+#define HCS12_MMC_MISC 0x0013 /* Miscellaneous System Control Register */
# define MMC_MISC_ROMON (1 << 0) /* Bit 0: Enable FLASH EEPROM or ROM */
# define MMC_MISC_ROMHM (1 << 1) /* Bit 1: FLASH EEPROM or ROM Only in Second Half of Memory Map */
# define MMC_MISC_EXSTR_SHIFT (3) /* Bits 3-7: External Access Stretch Bits */
@@ -74,10 +74,10 @@
# define MISC_EXSTR_CLKS2 (2 << MMC_MISC_EXSTR_SHIFT)
# define MISC_EXSTR_CLKS3 (3 << MMC_MISC_EXSTR_SHIFT)
-#define HC12_MMC_TESTREG0 0x0014 /* Reserved Test Register 0 */
-#define HC12_MMC_TESTREG1 0x0017 /* Reserved Test Register 1 */
+#define HCS12_MMC_TESTREG0 0x0014 /* Reserved Test Register 0 */
+#define HCS12_MMC_TESTREG1 0x0017 /* Reserved Test Register 1 */
-#define HC12_MMC_MEMSIZ0 0x001c /* Memory Size Register 0 */
+#define HCS12_MMC_MEMSIZ0 0x001c /* Memory Size Register 0 */
# define MMC_MEMSIZ0_RAMSW_SHIFT (0) /* Bits 0-2: Allocated System RAM Memory Space */
# define MMC_MEMSIZ0_RAMSW_MASK (7 << MMC_MEMSIZ0_RAMSW_SHIFT)
# define MEMSIZ0_RAMSW_2KB (0 << MMC_MEMSIZ0_RAMSW_SHIFT)
@@ -96,7 +96,7 @@
# define MEMSIZ0_EEPSW_5KB (3 << MMC_MEMSIZ0_EEPSW_MASK)
# define MMC_MEMSIZ0_REGSW (1 << 7) /* Bits 7: Allocated System Register Space */
-#define HC12_MMC_MEMSIZ1 0x001d /* Memory Size Register 1 */
+#define HCS12_MMC_MEMSIZ1 0x001d /* Memory Size Register 1 */
# define MMC_MEMSIZ1_PAGSW_SHIFT (0) /* Bits 0-1: Allocated System RAM Memory Space */
# define MMC_MEMSIZ1_PAGSW_MASK (3 << MMC_MEMSIZ1_PAGSW_SHIFT)
# define MEMSIZ1_PAGSW_128KB (0 << MMC_MEMSIZ1_PAGSW_SHIFT)
@@ -110,7 +110,7 @@
# define MEMSIZ1_ROMSW_48KB (2 << MMC_MEMSIZ1_ROMSW_SHIFT)
# define MEMSIZ1_ROMSW_64KB (3 << MMC_MEMSIZ1_ROMSW_SHIFT)
-#define HC12_MMC_PPAGE 0x0030 /* Program Page Index Register */
+#define HCS12_MMC_PPAGE 0x0030 /* Program Page Index Register */
# define MMC_PPAGE_PIX_SHIFT (0) /* Bits 0-5 Program Page Index Bits 5–0 */
# define MMC_PPAGE_PIX_MASK (0x3f << MMC_PPAGE_PIX_SHIFT)
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S
index e12c4a56d..75613d8a8 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S
@@ -41,6 +41,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include "mc9s12ne64_internal.h"
#include "mc9s12ne64_mmc.h"
#include "mc9s12ne64_crg.h"
@@ -60,49 +61,59 @@
* Macros
****************************************************************************/
+/* Print a character on the UART to show boot status. This macro will
+ * modify r0, r1, r2 and r14
+ */
+
+ .macro showprogress, code
+#if defined(CONFIG_DEBUG) && defined(CONFIG_HCS12_SERIALMON)
+ jsr #PutChar
+#endif
+ .endm
+
/* Memory map initialization */
.macro MMCINIT
- clr HC12_MMC_INITRG /* Set the register map position to 0x0000*/
+ movb #0x00, HCS12_MMC_INITRG /* Set the register map position to 0x0000*/
nop
- ldab #0x09
- stab *HC12_MMC_INITEE /* Set EEPROM position to 0x0800 */
-
-#ifdef CONFIG_HC12_SERIALMON
- ldab #0x39 /* Set RAM position to 0x3800 */
+#ifdef CONFIG_HCS12_SERIALMON
+ movb #0x39, HCS12_MMC_INITRM /* Set RAM position to 0x3800 to end at 0x3fff */
#else
- ldab #0x20 /* Set RAM position to 0x2000*/
+ movb #0x20, HCS12_MMC_INITRM /* Set RAM position to 0x2000*/
#endif
- stab *HC12_MMC_INITRM
- ldaa #MMC_MISC_ROMON /* MISC: EXSTR1=0 EXSTR0=0 ROMHM=0 ROMON=1 */
- staa *HC12_MMC_MISC
+
+ movb #0x09, HCS12_MMC_INITEE /* Set EEPROM position to 0x0800 */
+ movb #MMC_MISC_ROMON, HCS12_MMC_MISC /* MISC: EXSTR1=0 EXSTR0=0 ROMHM=0 ROMON=1 */
.endm
-/* System clock initialization */
+/* System clock initialization. If the serial monitor is used, then clocking will have
+ * already been configured at 24 MHz
+ */
.macro PLLINIT
-
+#ifndef CONFIG_HCS12_SERIALMON
/* Select the clock source from crystal */
- clr HC12_CRG_CLKSEL
+ clr HCS12_CRG_CLKSEL
/* Set the multipler and divider and enable the PLL */
- bclr *HC12_CRG_PLLCTL #CRG_PLLCTL_PLLON
+ bclr *HCS12_CRG_PLLCTL #CRG_PLLCTL_PLLON
ldab #15
- stab HC12_CRG_SYNR
- stab HC12_CRG_REFDV
- bset *HC12_CRG_PLLCTL #CRG_PLLCTL_PLLON
+ stab HCS12_CRG_SYNR
+ stab HCS12_CRG_REFDV
+ bset *HCS12_CRG_PLLCTL #CRG_PLLCTL_PLLON
/* Wait for the PLL to lock on */
.Lpll_lock:
- brclr *HC12_CRG_CRGFLG #CRG_CRGFLG_LOCK .Lpll_lock
+ brclr *HCS12_CRG_CRGFLG #CRG_CRGFLG_LOCK .Lpll_lock
/* Then select the PLL clock source */
- bset *HC12_CRG_CLKSEL #CRG_CLKSEL_PLLSEL
+ bset *HCS12_CRG_CLKSEL #CRG_CLKSEL_PLLSEL
+#endif
.endm
@@ -129,6 +140,7 @@ __start:
/* Setup the stack pointer */
lds .Lstackbase
+ showprogress 'A'
/* Clear BSS */
@@ -144,6 +156,7 @@ __start:
inx /* Address the next byte */
bra .Lclearbss /* And loop until all cleared */
.Lbsscleared:
+ showprogress 'B'
/* Initialize the data section */
@@ -160,9 +173,11 @@ __start:
inx /* Increment the destination address */
bra .Linitdata /* And loop until all of .DATA is initialized */
.Ldatainitialized:
+ showprogress 'C'
/* Now, start the OS */
+ showprogress '\n'
call os_start
bra __start
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_vectors.S b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_vectors.S
index 195cbfccd..47d793ba0 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_vectors.S
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_vectors.S
@@ -50,7 +50,7 @@
************************************************************************************/
.globl __start
- .file "mc9shc12ne64_vectors.S"
+ .file "mc9s12ne64_vectors.S"
/************************************************************************************
* Macros
@@ -64,12 +64,12 @@
* Vectors
************************************************************************************/
- .section .vectors, "x"
+ .section vectors, "x"
.align 2
- .globl hc12_vectors
- .type hc12_vectors, function
+ .globl hcs12_vectors
+ .type hcs12_vectors, function
-hc12_vectors:
+hcs12_vectors:
/* ff80-ff9f: Reserved */
.hword villegal /* ff80: Reserved*/
.hword villegal /* ff82: Reserved */
@@ -136,7 +136,7 @@ hc12_vectors:
.hword vclkmon /* fffc: Clock monitor fail reset */
.hword __start /* fffe: Reset vector */
- .size hc12_vectors, .-hc12_vectors
+ .size hcs12_vectors, .-hcs12_vectors
/************************************************************************************
* .text
@@ -146,44 +146,44 @@ hc12_vectors:
.type handlers, function
handlers:
- HANDLER vemacec, HC12_IRQ_VEMACEC /* EMAC excessive collision */
- HANDLER vemaclc, HC12_IRQ_VEMACLC /* EMAC late collision */
- HANDLER vemacbrxerr, HC12_IRQ_VEMACBRXERR /* EMAC babbling receive error */
- HANDLER vemacrxbbo, HC12_IRQ_VEMACRXBBO /* EMAC receive buffer B overrun */
- HANDLER vemacrxbao, HC12_IRQ_VEMACRXBAO /* EMAC receive buffer A overrun */
- HANDLER vemacrxerr, HC12_IRQ_VEMACRXERR /* EMAC receive error */
- HANDLER vemacmii, HC12_IRQ_VEMACMII /* EMAC MII management transfer complete */
- HANDLER vemacrxfc, HC12_IRQ_VEMACRXFC /* EMAC receive flow control */
- HANDLER vemactxc, HC12_IRQ_VEMACTXC /* EMAC frame transmission complete */
- HANDLER vemaccrxbbc, HC12_IRQ_VEMACCRXBBC /* EMAC receive buffer B complete */
- HANDLER vemaccrxbac, HC12_IRQ_VEMACCRXBAC /* EMAC receive buffer A complete */
- HANDLER vephy, HC12_IRQ_VEPHY /* EPHY interrupt */
- HANDLER vflash, HC12_IRQ_VFLASH /* FLASH */
- HANDLER viic, HC12_IRQ_VIIC /* IIC bus */
- HANDLER vcrgscm, HC12_IRQ_VCRGSCM /* CRG self clock mode */
- HANDLER vcrgplllck, HC12_IRQ_VCRGPLLLCK /* CRG PLL lock */
- HANDLER vportg, HC12_IRQ_VPORTG /* Port G */
- HANDLER vporth, HC12_IRQ_VPORTH /* Port H */
- HANDLER vportj, HC12_IRQ_VPORTJ /* Port J */
- HANDLER vatd, HC12_IRQ_VATD /* ATD */
- HANDLER vsci1, HC12_IRQ_VSCI1 /* SCI1 */
- HANDLER vsci0, HC12_IRQ_VSCI0 /* SCI0 */
- HANDLER vspi, HC12_IRQ_VSPI /* SPI */
- HANDLER vtimpaie, HC12_IRQ_VTIMPAIE /* Pulse accumulator input edge */
- HANDLER vtimpaovf, HC12_IRQ_VTIMPAOVF /* Pulse accumulator overflow */
- HANDLER vtimovf, HC12_IRQ_VTIMOVF /* Standard timer overflow */
- HANDLER vtimch7, HC12_IRQ_VTIMCH7 /* Standard timer channel 7 */
- HANDLER vtimch6, HC12_IRQ_VTIMCH6 /* Standard timer channel 6 */
- HANDLER vtimch5, HC12_IRQ_VTIMCH5 /* Standard timer channel 5 */
- HANDLER vtimch4, HC12_IRQ_VTIMCH4 /* Standard timer channel 4 */
- HANDLER vrti, HC12_IRQ_VRTI /* Real-time interrupt */
- HANDLER virq, HC12_IRQ_VIRQ /* IRQ */
- HANDLER vxirq, HC12_IRQ_VXIRQ /* XIRQ */
- HANDLER vswi, HC12_IRQ_VSWI /* SWI */
- HANDLER vtrap, HC12_IRQ_VTRAP /* Unimplemented instruction trap */
- HANDLER vcop, HC12_IRQ_VCOP /* COP failure reset*/
- HANDLER vclkmon, HC12_IRQ_VCLKMON /* Clock monitor fail reset */
- HANDLER villegal, HC12_IRQ_VILLEGAL /* Any reserved vector */
+ HANDLER vemacec, HCS12_IRQ_VEMACEC /* EMAC excessive collision */
+ HANDLER vemaclc, HCS12_IRQ_VEMACLC /* EMAC late collision */
+ HANDLER vemacbrxerr, HCS12_IRQ_VEMACBRXERR /* EMAC babbling receive error */
+ HANDLER vemacrxbbo, HCS12_IRQ_VEMACRXBBO /* EMAC receive buffer B overrun */
+ HANDLER vemacrxbao, HCS12_IRQ_VEMACRXBAO /* EMAC receive buffer A overrun */
+ HANDLER vemacrxerr, HCS12_IRQ_VEMACRXERR /* EMAC receive error */
+ HANDLER vemacmii, HCS12_IRQ_VEMACMII /* EMAC MII management transfer complete */
+ HANDLER vemacrxfc, HCS12_IRQ_VEMACRXFC /* EMAC receive flow control */
+ HANDLER vemactxc, HCS12_IRQ_VEMACTXC /* EMAC frame transmission complete */
+ HANDLER vemaccrxbbc, HCS12_IRQ_VEMACCRXBBC /* EMAC receive buffer B complete */
+ HANDLER vemaccrxbac, HCS12_IRQ_VEMACCRXBAC /* EMAC receive buffer A complete */
+ HANDLER vephy, HCS12_IRQ_VEPHY /* EPHY interrupt */
+ HANDLER vflash, HCS12_IRQ_VFLASH /* FLASH */
+ HANDLER viic, HCS12_IRQ_VIIC /* IIC bus */
+ HANDLER vcrgscm, HCS12_IRQ_VCRGSCM /* CRG self clock mode */
+ HANDLER vcrgplllck, HCS12_IRQ_VCRGPLLLCK /* CRG PLL lock */
+ HANDLER vportg, HCS12_IRQ_VPORTG /* Port G */
+ HANDLER vporth, HCS12_IRQ_VPORTH /* Port H */
+ HANDLER vportj, HCS12_IRQ_VPORTJ /* Port J */
+ HANDLER vatd, HCS12_IRQ_VATD /* ATD */
+ HANDLER vsci1, HCS12_IRQ_VSCI1 /* SCI1 */
+ HANDLER vsci0, HCS12_IRQ_VSCI0 /* SCI0 */
+ HANDLER vspi, HCS12_IRQ_VSPI /* SPI */
+ HANDLER vtimpaie, HCS12_IRQ_VTIMPAIE /* Pulse accumulator input edge */
+ HANDLER vtimpaovf, HCS12_IRQ_VTIMPAOVF /* Pulse accumulator overflow */
+ HANDLER vtimovf, HCS12_IRQ_VTIMOVF /* Standard timer overflow */
+ HANDLER vtimch7, HCS12_IRQ_VTIMCH7 /* Standard timer channel 7 */
+ HANDLER vtimch6, HCS12_IRQ_VTIMCH6 /* Standard timer channel 6 */
+ HANDLER vtimch5, HCS12_IRQ_VTIMCH5 /* Standard timer channel 5 */
+ HANDLER vtimch4, HCS12_IRQ_VTIMCH4 /* Standard timer channel 4 */
+ HANDLER vrti, HCS12_IRQ_VRTI /* Real-time interrupt */
+ HANDLER virq, HCS12_IRQ_VIRQ /* IRQ */
+ HANDLER vxirq, HCS12_IRQ_VXIRQ /* XIRQ */
+ HANDLER vswi, HCS12_IRQ_VSWI /* SWI */
+ HANDLER vtrap, HCS12_IRQ_VTRAP /* Unimplemented instruction trap */
+ HANDLER vcop, HCS12_IRQ_VCOP /* COP failure reset*/
+ HANDLER vclkmon, HCS12_IRQ_VCLKMON /* Clock monitor fail reset */
+ HANDLER villegal, HCS12_IRQ_VILLEGAL /* Any reserved vector */
/************************************************************************************
* Common IRQ handling logic