summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_head.S2
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S128
-rwxr-xr-xnuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_vectors.S2
-rwxr-xr-xnuttx/configs/demo9s12ne64/ostest/ld.script11
4 files changed, 115 insertions, 28 deletions
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_head.S b/nuttx/arch/arm/src/lpc214x/lpc214x_head.S
index bf8948f19..72d026aaa 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_head.S
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_head.S
@@ -552,7 +552,7 @@ __start:
* as possible. Modifies r0, r1, r2, and r14.
*/
- bl up_lowsetup
+ bl up_lowsetup
showprogress 'A'
/* Setup system stack (and get the BSS range) */
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S
index a818a68c2..e12c4a56d 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S
@@ -53,6 +53,7 @@
************************************************************************************/
.globl __start
+ .globl os_start
.file "mc9s12ne64_start.S"
/****************************************************************************
@@ -62,10 +63,20 @@
/* Memory map initialization */
.macro MMCINIT
- movb #0, HC12_MMC_INITRG /* Set the register map position */
+ clr HC12_MMC_INITRG /* Set the register map position to 0x0000*/
nop
- movb #32, HC12_MMC_INITRM /* Set the RAM map position */
- movb #1, HC12_MMC_MISC /* MISC: EXSTR1=0 EXSTR0=0 ROMHM=0 ROMON=1 */
+
+ ldab #0x09
+ stab *HC12_MMC_INITEE /* Set EEPROM position to 0x0800 */
+
+#ifdef CONFIG_HC12_SERIALMON
+ ldab #0x39 /* Set RAM position to 0x3800 */
+#else
+ ldab #0x20 /* 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
.endm
/* System clock initialization */
@@ -74,35 +85,33 @@
/* Select the clock source from crystal */
- movb #0, HC12_CRG_CLKSEL
- movb #CRG_CRGSEL_PLLSEL, HC12_CRG_CLKSEL
+ clr HC12_CRG_CLKSEL
/* Set the multipler and divider and enable the PLL */
- movb #0, HC12_CRG_PLLCTL
- movb #15, HC12_CRG_SYNR
- movb #15, HC12_CRG_REFDV
- movb #(CRG_PLLCTL_CME|CRG_PLLCTL_PLLON), HC12_CRG_PLLCTL
+ bclr *HC12_CRG_PLLCTL #CRG_PLLCTL_PLLON
+ ldab #15
+ stab HC12_CRG_SYNR
+ stab HC12_CRG_REFDV
+ bset *HC12_CRG_PLLCTL #CRG_PLLCTL_PLLON
/* Wait for the PLL to lock on */
.Lpll_lock:
- ldab HC12_CRG_CRGFLG
- clra
- andb #CRG_CRGFLG_LOCK
- ldx #0
- bne .Lpll_lock
- tbne d,.Lpll_lock
+ brclr *HC12_CRG_CRGFLG #CRG_CRGFLG_LOCK .Lpll_lock
- /* The select the PLL clock source */
+ /* Then select the PLL clock source */
- bset HC12_CRG_CLKSEL_OFFSET, #CRG_CLKSEL_PLLSEL
+ bset *HC12_CRG_CLKSEL #CRG_CLKSEL_PLLSEL
.endm
+
/****************************************************************************
* .text
****************************************************************************/
+ .section nonbanked, "x"
+
/****************************************************************************
* Name: __start
*
@@ -112,6 +121,87 @@
****************************************************************************/
__start:
- MMCINIT /* Initialize the MMC */
- PLLINIT /* Initialize the PLL */
+ /* Hardware setup */
+
+ MMCINIT /* Initialize the MMC */
+ PLLINIT /* Initialize the PLL */
+
+ /* Setup the stack pointer */
+
+ lds .Lstackbase
+
+ /* Clear BSS */
+
+ ldx .Lsbss /* Start of .BSS */
+ ldd .Lebss /* End+1 of .BSS */
+
+.Lclearbss:
+ pshd
+ cpx 2,sp+ /* Check if all BSS has been cleared */
+ beq .Lbsscleared /* If so, exit the loop */
+
+ clr 0,x /* Clear this byte */
+ inx /* Address the next byte */
+ bra .Lclearbss /* And loop until all cleared */
+.Lbsscleared:
+
+ /* Initialize the data section */
+
+ ldx .Lsdata /* Start of .DATA (destination) */
+ movw .Ledata, 0, sp /* End of .DATA (destination) */
+ ldy .Leronly /* Start of .DATA (source) */
+
+.Linitdata:
+ cpx 0, sp /* Check if all .DATA has been initialized */
+ beq .Ldatainitialized /* If so, exit the loop */
+ ldab 0, y /* Fetch the next byte from the source */
+ iny /* Increment the source address */
+ stab 0, x /* Store the byte to the destination */
+ inx /* Increment the destination address */
+ bra .Linitdata /* And loop until all of .DATA is initialized */
+.Ldatainitialized:
+
+ /* Now, start the OS */
+
+ call os_start
+ bra __start
+
+ /* Variables:
+ * _sbss is the start of the BSS region (see ld.script)
+ * _ebss is the end of the BSS regsion (see ld.script)
+ * The idle task stack starts at the end of BSS and is
+ * of size CONFIG_IDLETHREAD_STACKSIZE. The heap continues
+ * from there until the end of memory. See g_heapbase
+ * below.
+ */
+
+.Lsbss:
+ .long _sbss
+.Lebss:
+ .long _ebss
+.Lstackbase:
+ .hword _ebss+CONFIG_IDLETHREAD_STACKSIZE-4
+.Leronly:
+ .long _eronly /* Where .data defaults are stored in FLASH */
+.Lsdata:
+ .long _sdata /* Where .data needs to reside in SDRAM */
+.Ledata:
+ .long _edata
+ .size __start, .-__start
+
+ /* This global variable is unsigned long g_heapbase and is
+ * exported from here only because of its coupling to LCO
+ * above.
+ */
+
+ .data
+ .align 4
+ .globl g_heapbase
+ .type g_heapbase, object
+g_heapbase:
+ .long _ebss+CONFIG_IDLETHREAD_STACKSIZE
+ .size g_heapbase, .-g_heapbase
+
+ .end
+
.end
diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_vectors.S b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_vectors.S
index 42dbe0fd9..195cbfccd 100755
--- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_vectors.S
+++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_vectors.S
@@ -64,7 +64,7 @@
* Vectors
************************************************************************************/
- .section .vectors, "rd"
+ .section .vectors, "x"
.align 2
.globl hc12_vectors
.type hc12_vectors, function
diff --git a/nuttx/configs/demo9s12ne64/ostest/ld.script b/nuttx/configs/demo9s12ne64/ostest/ld.script
index 1b7b628ee..e6fa37686 100755
--- a/nuttx/configs/demo9s12ne64/ostest/ld.script
+++ b/nuttx/configs/demo9s12ne64/ostest/ld.script
@@ -33,17 +33,14 @@
*
****************************************************************************/
-/* The DEMO9S12NE64 has 512Kb of FLASH beginning at address 0x0800:0000 and
- * 64Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH,
- * FLASH memory is aliased to address 0x0000:0000 where the code expects to
- * begin execution by jumping to the entry point in the 0x0800:0000 address
- * range.
+/* The DEMO9S12NE64 has 64Kb of FLASH and 8Kb of SRAM that are assumed to be
+ * positioned as below:
*/
MEMORY
{
- flash (rx) : ORIGIN = 0x08000000, LENGTH = 512K
- sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
+ flash (rx) : ORIGIN = 0x0800, LENGTH = 64K
+ sram (rwx) : ORIGIN = 0x3800, LENGTH = 8K
}
OUTPUT_ARCH(m68hc12)