summaryrefslogtreecommitdiff
path: root/nuttx/arch/hc
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-11 21:55:37 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-11 21:55:37 +0000
commit85e0e91f408ee6c26e6eeb07742a73d3871215ce (patch)
tree602367f4ce80060ed8e6465cfa1c237b57725105 /nuttx/arch/hc
parentd8ac0a01d815d109e177b6f752806f8512c4319e (diff)
downloadpx4-nuttx-85e0e91f408ee6c26e6eeb07742a73d3871215ce.tar.gz
px4-nuttx-85e0e91f408ee6c26e6eeb07742a73d3871215ce.tar.bz2
px4-nuttx-85e0e91f408ee6c26e6eeb07742a73d3871215ce.zip
Flash layout, bootloader, paging fixes
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2321 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/hc')
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/chip.h41
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h48
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_flash.h210
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_internal.h9
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S6
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h27
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S32
7 files changed, 313 insertions, 60 deletions
diff --git a/nuttx/arch/hc/src/mc9s12ne64/chip.h b/nuttx/arch/hc/src/mc9s12ne64/chip.h
index f8f8b0e21..cb8df40d8 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/chip.h
+++ b/nuttx/arch/hc/src/mc9s12ne64/chip.h
@@ -47,7 +47,46 @@
* Definitions
************************************************************************************/
-#define HCS12_MODULE_BASE 0x0000
+/* Memory Map.
+ *
+ * At reset:
+ * 0x0000–0x03ff: register space
+ * 0x0000–0x1fff: 7K RAM (1K RAM hidden behind register space)
+ */
+
+#define HCS12_REG_BASE 0x0000 /* 0x0000-0x03ff: Mapped Register base address */
+#define HCS12_EEPROM_BASE 0x0800 /* 0x0800: Mapped EEPROM base address */
+#define HCS12_SRAM_BASE 0x2000 /* 0x2000-0x3fff: Mapped SRAM base address */
+#define HCS12_FFLASH1_BASE 0x4000 /* 0x4000-0x7fff: 16Kb Fixed FLASH EEPROM */
+#define HCS12_PPAGE_BASE 0x8000 /* 0x8000-0xbfff: 16Kb Page window */
+#define HCS12_FFLASH2_BASE 0xc000 /* 0xc000-0xffff: 16Kb Fixed FLASH EEPROM */
+
+/* Device Register Map Overview (all relatvie to HCS12_REG_BASE) */
+
+#define HCS12_CORE1_BASE 0x0000 /* 0x0000–0x0017: Ports A, B, E, Modes, Inits (MMC, INT, MEBI) */
+ /* 0x0018–0x0019: Reserved */
+#define HCS12_DEVID_BASE 0x001a /* 0x001a-0x001b: Device ID register (PARTID) */
+#define HCS12_CORE2_BASE 0x001C /* 0x001c–0x001f: MEMSIZ, IRQ, HPRIO (INT, MMC) */
+#define HCS12_CORE3_BASE 0x0020 /* 0x0020-0x002f: DBG */
+#define HCS12_CORE4_BASE 0x0030 /* 0x0030–0x0033: PPAGE, Port K (MEBI, MMC) */
+#define HCS12_CRG_BASE 0x0034 /* 0x0034–0x003f: Clock and Reset Generator (PLL, RTI, COP) */
+#define HCS12_TIM_BASE 0x0040 /* 0x0040–0x006f: Standard Timer 16-bit 4 channels (TIM) */
+ /* 0x0070–0x007f: Reserved */
+#define HCS12_ATD_BASE 0x0080 /* 0x0080–0x009f: Analog-to-Digital Converter 10-bit, 8-channel (ATD) */
+ /* 0x00a0–0x00c7: Reserved */
+#define HCS12_SCI0_BASE 0x00c8 /* 0x00c8–0x00cf: Serial Communications Interface 0 (SCI0) */
+#define HCS12_SCI1_BASE 0x00d0 /* 0x00d0–0x00d7: Serial Communications Interface 1 (SCI1) */
+#define HCS12_SPI_BASE 0x00d8 /* 0x00d8–0x00df: Serial Peripheral Interface (SPI) */
+#define HCS12_IIC_BASE 0x00e0 /* 0x00e0–0x00e7: Inter IC Bus (IIC) */
+ /* 0x00e8–0x00ff: Reserved */
+#define HCS12_FLASH_BASE 0x0100 /* 0x0100–0x010f: FLASH Control Register */
+ /* 0x0110–0x011f: Reserved */
+#define HCS12_EPHY_BASE 0x0120 /* 0x0120–0x0123: Ethernet Physical Interface (EPHY) */
+ /* 0x0124–0x013f: Reserved */
+#define HCS12_EMAC_BASE 0x0140 /* 0x0140–0x016f: Ethernet Media Access Controller (EMAC) */
+ /* 0x0170–0x023f: Reserved */
+#define HCS12_PIM_BASE 0x0240 /* 0x0240–0x026f: Port Integration Module (PIM) */
+ /* 0x0270–0x03ff: Reserved */
/************************************************************************************
* Public Types
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h
index 3731621fb..cd4794fc2 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 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 */
+#define HCS12_CRG_SYNR_OFFSET (HCS12_CRG_BASE+0x00) /* CRG Synthesizer Register */
+#define HCS12_CRG_REFDV_OFFSET (HCS12_CRG_BASE+0x01) /* CRG Reference Divider Register */
+#define HCS12_CRG_CTFLG_OFFSET (HCS12_CRG_BASE+0x02) /* CRG Test Flags Register */
+#define HCS12_CRG_CRGFLG_OFFSET (HCS12_CRG_BASE+0x03) /* CRG Flags Register */
+#define HCS12_CRG_CRGINT_OFFSET (HCS12_CRG_BASE+0x04) /* CRG Interrupt Enable Register */
+#define HCS12_CRG_CLKSEL_OFFSET (HCS12_CRG_BASE+0x05) /* CRG Clock Select Register */
+#define HCS12_CRG_PLLCTL_OFFSET (HCS12_CRG_BASE+0x06) /* CRG PLL Control Register */
+#define HCS12_CRG_RTICTL_OFFSET (HCS12_CRG_BASE+0x07) /* CRG RTI Control Register */
+#define HCS12_CRG_COPCTL_OFFSET (HCS12_CRG_BASE+0x08) /* CRG COP Control Register */
+#define HCS12_CRG_FORBYP_OFFSET (HCS12_CRG_BASE+0x09) /* CRG Force and Bypass Test Register */
+#define HCS12_CRG_CTCTL_OFFSET (HCS12_CRG_BASE+0x0a) /* CRG Test Control Register */
+#define HCS12_CRG_ARMCOP_OFFSET (HCS12_CRG_BASE+0x0b) /* CRG COP Arm/Timer Reset */
/* CRG Module Register Addresses */
-#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)
+#define HCS12_CRG_SYNR (HCS12_REG_BASE+HCS12_CRG_SYNR_OFFSET)
+#define HCS12_CRG_REFDV (HCS12_REG_BASE+HCS12_CRG_REFDV_OFFSET)
+#define HCS12_CRG_CTFLG (HCS12_REG_BASE+HCS12_CRG_CTFLG_OFFSET)
+#define HCS12_CRG_CRGFLG (HCS12_REG_BASE+HCS12_CRG_CRGFLG_OFFSET)
+#define HCS12_CRG_CRGINT (HCS12_REG_BASE+HCS12_CRG_CRGINT_OFFSET)
+#define HCS12_CRG_CLKSEL (HCS12_REG_BASE+HCS12_CRG_CLKSEL_OFFSET)
+#define HCS12_CRG_PLLCTL (HCS12_REG_BASE+HCS12_CRG_PLLCTL_OFFSET)
+#define HCS12_CRG_RTICTL (HCS12_REG_BASE+HCS12_CRG_RTICTL_OFFSET)
+#define HCS12_CRG_COPCTL (HCS12_REG_BASE+HCS12_CRG_COPCTL_OFFSET)
+#define HCS12_CRG_FORBYP (HCS12_REG_BASE+HCS12_CRG_FORBYP_OFFSET)
+#define HCS12_CRG_CTCTL (HCS12_REG_BASE+HCS12_CRG_CTCTL_OFFSET)
+#define HCS12_CRG_ARMCOP (HCS12_REG_BASE+HCS12_CRG_ARMCOP_OFFSET)
/* CRG Module Register Bit Definitions */
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_flash.h b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_flash.h
new file mode 100755
index 000000000..44164f5fe
--- /dev/null
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_flash.h
@@ -0,0 +1,210 @@
+/************************************************************************************
+ * arch/hc/src/mc9s12ne64/mc9s12ne64_flash.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_ARM_HC_SRC_MC9S12NE64_MC9S12NE64_FLASH_H
+#define __ARCH_ARM_HC_SRC_MC9S12NE64_MC9S12NE64_FLASH_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include "chip.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Flash memory map *****************************************************************
+ *
+ * 0x4000-0x7fff: 16Kb Fixed FLASH EEPROM (Page 3e)
+ * 0x8000-0xbfff: 16Kb Page window
+ * 0xc000-0xffff: 16Kb Fixed FLASH EEPROM (Page 3f)
+ * (see chip.h)
+ *
+ * The MC9S12NE64 implements 6 bits of the PPAGE register which gives it a
+ * 1 Mbyte program memory address space that is accessed through the PPAGE
+ * window. The lower 768K portion of the address space, accessed with PPAGE
+ * values $00 through $2F, is reserved for external memory when the part is
+ * operated in expanded mode. The upper 256K of the address space, accessed
+ * with PPAGE values $30 through $3F.
+ */
+
+#define HCS12_BTLDR_BASE 0xf800 /* 0xf800-0xffff: 2Kb Protected bootloader FLASH */
+
+/* User-Accessible utility subroutines provided by the serial monitor:
+ *
+ * PutChar - Sends the character in A out SCI0
+ *
+ * PutChar: brclr SCI0SR1,TDRE,PutChar ;wait for Tx ready
+ * staa SCI0DRL ;send character from A
+ * rts
+ *
+ * GetChar - Wait indefinitely for a character to be received via SCI.
+ * Return received character in A.
+ *
+ * GetChar: brset SCI0SR1,RDRF,RxReady ;exit loop when RDRF=1
+ * bra GetChar ;loop till RDRF set
+ * RxReady: ldaa SCI0DRL ;read character into A
+ * rts ;return
+ * EraseAllCmd - Use repeated page erase commands to erase all flash
+ * except bootloader in protected block at the end of flash, and mass
+ * erase all EEPROM locations
+ * DoOnStack - Copy to stack and execute from RAM
+ * WriteD2IX - Write the data in D (word) to the address in IX
+ * The location may be RAM, FLASH, EEPROM, or a register
+ * if FLASH or EEPROM, the operation is completed before return
+ * IX and A preserved, returns Z=1 (.EQ.) if OK
+ */
+
+#ifdef CONFIG_HCS12_SERIALMON
+# 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 */
+
+/* Serial monitor version */
+
+# define SWID_DEVID 0xfef8
+# define SWID_DATE 0xfefa
+# define SWID_YEAR 0xfefc
+# define SWID_VER 0xfefe
+
+/* Interrupts */
+
+# define HCS12_UVECTOR_BASE 0xf780 /* 0xf780–0xf7fe: User vector base */
+#endif
+
+/* FLASH interface */
+
+#define HCS12_BACKDOOR_KEY 0xff00 /* 0xff00-0xff07: Backdoor comparison keys */
+ /* 0xff08-0xff0c: Reserved */
+#define HCS12_FLASH_PROT 0xff0d /* 0xff0d: Flash protection byte */
+ /* 0xff0e: Reserved */
+#define HCS12_FLASH_OPT 0xff0f /* 0xff0f: Flash options/security byte */
+
+/* Interrupts */
+
+#define HCS12_VECTOR_BASE 0xff80 /* 0xff80–0xfffe: Actual vector base */
+
+/* Register Offsets *****************************************************************/
+
+#define HCS12_FLASH_FCLKDIV_OFFSET (HCS12_FLASH_BASE+0x00) /* Flash Clock Divider Register */
+#define HCS12_FLASH_FSEC_OFFSET (HCS12_FLASH_BASE+0x03) /* Flash Security Register */
+#define HCS12_FLASH_FCNFG_OFFSET (HCS12_FLASH_BASE+0x03) /* Flash Configuration Register */
+#define HCS12_FLASH_FPROT_OFFSET (HCS12_FLASH_BASE+0x04) /* Flash Protection Register */
+#define HCS12_FLASH_FSTAT_OFFSET (HCS12_FLASH_BASE+0x05) /* Flash Status Register */
+#define HCS12_FLASH_FCMD_OFFSET (HCS12_FLASH_BASE+0x06) /* Flash Command Register */
+#define HCS12_FLASH_FADDRHI_OFFSET (HCS12_FLASH_BASE+0x08) /* Flash High Address Register */
+#define HCS12_FLASH_FADDRLO_OFFSET (HCS12_FLASH_BASE+0x09) /* Flash Low Address Register */
+#define HCS12_FLASH_FDATAHI_OFFSET (HCS12_FLASH_BASE+0x0a) /* Flash High Data Register */
+#define HCS12_FLASH_FDATALO_OFFSET (HCS12_FLASH_BASE+0x0b) /* Flash Low Data Register (*/
+
+/* Register Addresses ***************************************************************/
+
+#define HCS12_FLASH_FCLKDIV (HCS12_REG_BASE+HCS12_FLASH_FCLKDIV_OFFSET)
+#define HCS12_FLASH_FSEC (HCS12_REG_BASE+HCS12_FLASH_FSEC_OFFSET)
+#define HCS12_FLASH_FCNFG (HCS12_REG_BASE+HCS12_FLASH_FCNFG_OFFSET)
+#define HCS12_FLASH_FPROT (HCS12_REG_BASE+HCS12_FLASH_FPROT_OFFSET)
+#define HCS12_FLASH_FSTAT (HCS12_REG_BASE+HCS12_FLASH_FSTAT_OFFSET)
+#define HCS12_FLASH_FCMD (HCS12_REG_BASE+HCS12_FLASH_FCMD_OFFSET)
+#define HCS12_FLASH_FADDRHI (HCS12_REG_BASE+HCS12_FLASH_FADDRHI_OFFSET)
+#define HCS12_FLASH_FADDRLO (HCS12_REG_BASE+HCS12_FLASH_FADDRLO_OFFSET)
+#define HCS12_FLASH_FDATAHI (HCS12_REG_BASE+HCS12_FLASH_FDATAHI_OFFSET)
+#define HCS12_FLASH_FDATALO (HCS12_REG_BASE+HCS12_FLASH_FDATALO_OFFSET)
+
+/* Register Bit Definitions *********************************************************/
+
+#define FLASH_FCLKDIV_FDIV_SHIFT (0) /* Bits 0-5: Clock Divider Bits */
+#define FLASH_FCLKDIV_FDIV_MASK (0x3f << FLASH_FCLKDIV_FDIV_SHIFT)
+#define FLASH_FCLKDIV_PRDIV8 (1 << 6) /* Bit 6: Enable Prescaler by 8 */
+#define FLASH_FCLKDIV_FDIVLD (1 << 7) /* Bit 7: Clock Divider Loaded */
+
+#define FLASH_FSET_SEC_SHIFT (0) /* Bits 0-1: Memory Security Bits */
+#define FLASH_FSET_SEC_MASK (3 << FLASH_FSET_SEC_SHIFT)
+# define FLASH_FSET_SEC_UNSECURED (2 << FLASH_FSET_SEC_SHIFT)
+#define FLASH_FSET_KEYEN (1 << 7) /* Bit 7: Backdoor Key Enable */
+#define FLASH_FSET_NV_SHIFT (2) /* Bits 2-6: Nonvolatile Flag Bits */
+#define FLASH_FSET_NV_MASK (0x1f << FLASH_FSET_NV_SHIFT)
+
+#define FLASH_FCNG_KEYACC (1 << 5) /* Bit 5: Enable Security Key Writing */
+#define FLASH_FCNG_CCIE (1 << 6) /* Bit 6: Command Complete Interrupt Enable */
+#define FLASH_FCNG_CBEIE (1 << 7) /* Bit 7: Command Buffer Empty Interrupt Enable */
+
+#define FLASH_FPROT_FPLS_SHIFT (0) /* Bits 0-1: Flash Protection Lower Address Size */
+#define FLASH_FPROT_FPLS_MASK (3 << FLASH_FPROT_FPLS_SHIFT)
+# define FLASH_FPROT_FPLS_512B (0 << FLASH_FPROT_FPLS_SHIFT)
+# define FLASH_FPROT_FPLS_1KB (1 << FLASH_FPROT_FPLS_SHIFT)
+# define FLASH_FPROT_FPLS_2KB (2 << FLASH_FPROT_FPLS_SHIFT)
+# define FLASH_FPROT_FPLS_4KB (3 << FLASH_FPROT_FPLS_SHIFT)
+#define FLASH_FPROT_FPLDIS (1 << 2) /* Bit 2: Flash Protection Lower address range Disable */
+#define FLASH_FPROT_FPHS_SHIFT (3) /* Bits 3-4: Flash Protection Higher Address Size */
+#define FLASH_FPROT_FPHS_MASK (3 << FLASH_FPROT_FPHS_SHIFT)
+# define FLASH_FPROT_FPHS_2KB (0 << FLASH_FPROT_FPHS_SHIFT)
+# define FLASH_FPROT_FPHS_4KB (1 << FLASH_FPROT_FPHS_SHIFT)
+# define FLASH_FPROT_FPHS_8KB (2 << FLASH_FPROT_FPHS_SHIFT)
+# define FLASH_FPROT_FPHS_16KB (3 << FLASH_FPROT_FPHS_SHIFT)
+#define FLASH_FPROT_FPHDIS (1 << 5) /* Bit 5: Flash Protection Higher address range disable */
+#define FLASH_FPROT_FPOPEN (1 << 7) /* Bit 7: Opens the Flash block for program or erase */
+
+#define FLASH_FSTAT_BLANK (1 << 2) /* Bit 2: Array has been verified as erased */
+#define FLASH_FSTAT_ACCERR (1 << 4) /* Bit 4: Flash access error */
+#define FLASH_FSTAT_PVIOL (1 << 5) /* Bit 5: Protection violation */
+#define FLASH_FSTAT_CCIF (1 << 6) /* Bit 6: Command complete interrupt flag */
+#define FLASH_FSTAT_CBEIF (1 << 7) /* Bit 7: Command buffer empty interrupt flag */
+
+#define FLASH_FCMD_ERASEVERIFY 0x05 /* Erase Verify */
+#define FLASH_FCMD_WORDPROGRM 0x20 /* Word Program */
+#define FLASH_FCMD_SECTORERASE 0x40 /* Sector Erase */
+#define FLASH_FCMD_MASSERASE 0x41 /* Mass Erase */
+
+#define FLASH_FADDRHI_MASK 0x7f
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_HC_SRC_MC9S12NE64_MC9S12NE64_FLASH_H */
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_internal.h b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_internal.h
index 1db25a19b..5bc0677c3 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_internal.h
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_internal.h
@@ -52,15 +52,6 @@
/* 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
************************************************************************************/
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S
index 05777546c..aaa0d4089 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_lowputc.S
@@ -38,10 +38,10 @@
**************************************************************************/
#include <nuttx/config.h>
-#include "up_internal.h"
-#include "up_arch.h"
+#include "up_internal.h"
#include "mc9s12ne64_internal.h"
+#include "mc9s12ne64_flash.h"
/**************************************************************************
* Private Definitions
@@ -95,7 +95,7 @@ up_lowsetup:
.type up_lowputc, function
up_lowputc:
#ifdef CONFIG_HCS12_SERIALMON
- bra PutChar
+ jmp PutChar
#else
# error "up_lowputc not implemented"
#endif
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h
index 11ecc2636..d1b29991e 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h
@@ -50,21 +50,24 @@
/* MMC Sub-block */
-#define HCS12_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 MMC_INITRM_RAM(addr) (((addr) >> (11-MMC_INITRM_RAM_SHIFT)) & MMC_INITRM_RAM_MASK)
-#define HCS12_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 MMC_INITRG_REG(addr) (((addr) >> (11-MMC_INITRG_REG_SHIFT)) & MMC_INITRG_REG_SHIFT)
-#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 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 MMC_INITEE_EE(addr) (((addr) >> (11-MMC_INITRG_REG_SHIFT)) & MMC_INITRG_REG_SHIFT)
-#define HCS12_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 +77,10 @@
# define MISC_EXSTR_CLKS2 (2 << MMC_MISC_EXSTR_SHIFT)
# define MISC_EXSTR_CLKS3 (3 << MMC_MISC_EXSTR_SHIFT)
-#define HCS12_MMC_TESTREG0 0x0014 /* Reserved Test Register 0 */
-#define HCS12_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 HCS12_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 +99,7 @@
# define MEMSIZ0_EEPSW_5KB (3 << MMC_MEMSIZ0_EEPSW_MASK)
# define MMC_MEMSIZ0_REGSW (1 << 7) /* Bits 7: Allocated System Register Space */
-#define HCS12_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 +113,7 @@
# define MEMSIZ1_ROMSW_48KB (2 << MMC_MEMSIZ1_ROMSW_SHIFT)
# define MEMSIZ1_ROMSW_64KB (3 << MMC_MEMSIZ1_ROMSW_SHIFT)
-#define HCS12_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 75613d8a8..c99ca3a15 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S
@@ -44,14 +44,19 @@
#include "mc9s12ne64_internal.h"
#include "mc9s12ne64_mmc.h"
#include "mc9s12ne64_crg.h"
+#include "mc9s12ne64_flash.h"
/****************************************************************************
* Private Definitions
****************************************************************************/
-/************************************************************************************
+#define INITRG_REG (MMC_INITRG_REG(HCS12_REG_BASE))
+#define INITRM_MAP (MMC_INITRM_RAM(HCS12_SRAM_BASE)|MMC_INITRM_RAMHAL)
+#define INITEE_EE (MMC_INITEE_EE(HCS12_EEPROM_BASE)|MMC_INITEE_EEON)
+
+/****************************************************************************
* Global Symbols
- ************************************************************************************/
+ ****************************************************************************/
.globl __start
.globl os_start
@@ -71,19 +76,24 @@
#endif
.endm
-/* Memory map initialization */
-
+/* Memory map initialization.
+ *
+ * The MC9S12NE64 has 64K bytes of FLASH EEPROM and 8K bytes of RAM.
+ */
+
.macro MMCINIT
- movb #0x00, HCS12_MMC_INITRG /* Set the register map position to 0x0000*/
+ /* Registers are always positioned at address 0x0000 */
+
+ movb #INITRG_REG, HCS12_MMC_INITRG /* Set the register map position to 0x0000*/
nop
-#ifdef CONFIG_HCS12_SERIALMON
- movb #0x39, HCS12_MMC_INITRM /* Set RAM position to 0x3800 to end at 0x3fff */
-#else
- movb #0x20, HCS12_MMC_INITRM /* Set RAM position to 0x2000*/
-#endif
+ /* Position SRAM so that is ends at address 0x3fff. This is required
+ * because the Freescale serial monitor initializes its stack to the
+ * end+1 of SRAM which it expects to be at address 0x4000
+ */
- movb #0x09, HCS12_MMC_INITEE /* Set EEPROM position to 0x0800 */
+ movb #INITRM_MAP, HCS12_MMC_INITRM /* Set RAM position to 0x2000-0x3fff */
+ movb #INITEE_EE, 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