From 97715862e3afa85cb26afacf60f629fa33eed1f7 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 3 Dec 2009 20:21:53 +0000 Subject: Some HC12 start-up logic git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2302 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/hc/src/mc9s12ne64/chip.h | 2 + nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h | 141 ++++++++++++++++++++++++ nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h | 129 ++++++++++++++++++++++ nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S | 67 +++++++++-- 4 files changed, 330 insertions(+), 9 deletions(-) create mode 100755 nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h create mode 100755 nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h (limited to 'nuttx/arch/hc') diff --git a/nuttx/arch/hc/src/mc9s12ne64/chip.h b/nuttx/arch/hc/src/mc9s12ne64/chip.h index a7dfdb26a..0f9afce84 100755 --- a/nuttx/arch/hc/src/mc9s12ne64/chip.h +++ b/nuttx/arch/hc/src/mc9s12ne64/chip.h @@ -47,6 +47,8 @@ * Definitions ************************************************************************************/ +#define HC12_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 new file mode 100755 index 000000000..40e3b82fe --- /dev/null +++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h @@ -0,0 +1,141 @@ +/************************************************************************************ + * arch/hc/src/mc9s12ne64/mc9s12ne64_crg.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_CRG_H +#define __ARCH_ARM_HC_SRC_MC9S12NE64_MC9S12NE64_CRG_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include +#include "chip.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* 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 */ + +/* 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) + +/* CRG Module Register Bit Definitions */ + +#define CRG_SYNR_SHIFT (0) /* Bits 0-5: CRG synthesizer value */ +#define CRG_SYNR_MASK (0x3f << CRG_SYNR_SHIFT) + +#define CRG_REFDV_SHIFT (0) /* Bit 0-3: Reference divider */ +#define CRG_REFDV_MASK (15 << CRG_REFDV_SHIFT) + +#define CRG_CRGFLG_SCM (1 << 0) /* Bit 0: Self-Clock Mode Status Bit */ +#define CRG_CRGFLG_SCMIF (1 << 1) /* Bit 1: Self-Clock Mode Interrupt Flag */ +#define CRG_CRGFLG_TRACK (1 << 2) /* Bit 2: Track Status Bit */ +#define CRG_CRGFLG_LOCK (1 << 3) /* Bit 3: Lock Status Bit */ +#define CRG_CRGFLG_LOCKIF (1 << 4) /* Bit 4: PLL Lock Interrupt Flag */ +#define CRG_CRGFLG_LVRF (1 << 5) /* Bit 5: Low Voltage Reset Flag */ +#define CRG_CRGFLG_PORF (1 << 6) /* Bit 6: Power-on Reset Flag */ +#define CRG_CRGFLG_RTIF (1 << 7) /* Bit 7: Real-Time Interrupt Flag */ + +#define CRG_CRGINT_SCMIE (1 << 1) /* Bit 1: Self-Clock Mode Status Bit */ +#define CRG_CRGINT_LOCKIE (1 << 4) /* Bit 4: Lock Interrupt Enable Bit */ +#define CRG_CRGINT_RTIE (1 << 7) /* Bit 7: Lock Interrupt Enable Bit */ + +#define CRG_CLKSEL_COPWAI (1 << 0) /* Bit 0: COP stops in Wait Mode Bit */ +#define CRG_CLKSEL_RTIWAI (1 << 1) /* Bit 1: RTI stops in Wait Mode Bit */ +#define CRG_CLKSEL_CWAI (1 << 2) /* Bit 2: Core stops in Wait Mode Bit */ +#define CRG_CLKSEL_PLLWAI (1 << 3) /* Bit 3: PLL stops in Wait Mode Bit */ +#define CRG_CLKSEL_ROAWAI (1 << 4) /* Bit 4: Reduced Oscillator Amplitude in Wait Mode Bit */ +#define CRG_CLKSEL_SYSWAI (1 << 5) /* Bit 5: System clocks stop in wait mode bit */ +#define CRG_CLKSEL_PSTP (1 << 6) /* Bit 6: Pseudo-Stop Bit */ +#define CRG_CLKSEL_PLLSEL (1 << 7) /* Bit 7: PLL Select Bit */ + +#define CRG_PLLCTL_SCME (1 << 0) /* Bit 0: Self-Clock Mode Enable Bit */ +#define CRG_PLLCTL_PCE (1 << 1) /* Bit 1: COP Enable during Pseudo-Stop Bit */ +#define CRG_PLLCTL_PRE (1 << 2) /* Bit 2: RTI Enable during Pseudo-Stop Bit */ +#define CRG_PLLCTL_ACQ (1 << 4) /* Bit 4: Acquisition Bit */ +#define CRG_PLLCTL_AUTO (1 << 5) /* Bit 5: Automatic Bandwidth Control Bit */ +#define CRG_PLLCTL_PLLON (1 << 6) /* Bit 6: Phase Lock Loop On Bit */ +#define CRG_PLLCTL_CME (1 << 7) /* Bit 7: Clock Monitor Enable Bit */ + +#define CRG_RTICTL_MODCNT_SHIFT (0) /* Bits 0-3: Real-Time Interrupt Modulus Counter Select Bits */ +#define CRG_RTICTL_MODCNT_MASK (15 << CRG_RTICTL_MODCNT_SHIFT) +#define CRG_RTICTL_PRER_SHIFT (4) /* Bits 4-6: Real-Time Interrupt Prescale Rate Select Bits */ +#define CRG_RTICTL_PRER_MASK (7 << CRG_RTICTL_PRE_SHIFT) + +#define CRG_COPCTL_CR_SHIFT (0) /* Bits 0-2: COP Watchdog Timer Rate select */ +#define CRG_COPCTL_CR_MASK (7 << CRG_COPCTL_CR_SHIFT) +#define CRG_COPCTL_RSBCK (1 << 6) /* Bit 6: COP and RTI stop in Active BDM mode B */ +#define CRG_COPCTL_WCOP (1 << 7) /* Bit 7: Window COP Mode Bit */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_HC_SRC_MC9S12NE64_MC9S12NE64_CRG_H */ diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h new file mode 100755 index 000000000..12d4f7b17 --- /dev/null +++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h @@ -0,0 +1,129 @@ +/************************************************************************************ + * arch/hc/src/mc9s12ne64/mc9s12ne64_mmc.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_MMC_H +#define __ARCH_ARM_HC_SRC_MC9S12NE64_MC9S12NE64_MMC_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include +#include "chip.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* MMC Sub-block */ + +#define HC12_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 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 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 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 */ +# define MMC_MISC_EXSTR_MASK (0x1f << MMC_MISC_EXSTR_SHIFT) +# define MISC_EXSTR_CLKS0 (0 << MMC_MISC_EXSTR_SHIFT) +# define MISC_EXSTR_CLKS1 (1 << MMC_MISC_EXSTR_SHIFT) +# 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 HC12_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) +# define MEMSIZ0_RAMSW_4KB (1 << MMC_MEMSIZ0_RAMSW_SHIFT) +# define MEMSIZ0_RAMSW_6KB (2 << MMC_MEMSIZ0_RAMSW_SHIFT) +# define MEMSIZ0_RAMSW_8KB (3 << MMC_MEMSIZ0_RAMSW_SHIFT) +# define MEMSIZ0_RAMSW_10KB (4 << MMC_MEMSIZ0_RAMSW_SHIFT) +# define MEMSIZ0_RAMSW_12KB (5 << MMC_MEMSIZ0_RAMSW_SHIFT) +# define MEMSIZ0_RAMSW_14KB (6 << MMC_MEMSIZ0_RAMSW_SHIFT) +# define MEMSIZ0_RAMSW_16KB (7 << MMC_MEMSIZ0_RAMSW_SHIFT) +# define MMC_MEMSIZ0_EEPSW_SHIFT (4) /* Bits 4-5: Allocated EEPROM Memory Space */ +# define MMC_MEMSIZ0_EEPSW_MASK (3 << MMC_MEMSIZ0_EEPSW_SHIFT) +# define MEMSIZ0_EEPSW_OKB (0 << MMC_MEMSIZ0_EEPSW_MASK) +# define MEMSIZ0_EEPSW_2KB (1 << MMC_MEMSIZ0_EEPSW_MASK) +# define MEMSIZ0_EEPSW_4KB (2 << MMC_MEMSIZ0_EEPSW_MASK) +# 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 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) +# define MEMSIZ1_PAGSW_256KB (1 << MMC_MEMSIZ1_PAGSW_SHIFT) +# define MEMSIZ1_PAGSW_512KB (2 << MMC_MEMSIZ1_PAGSW_SHIFT) +# define MEMSIZ1_PAGSW_1MB (3 << MMC_MEMSIZ1_PAGSW_SHIFT) +# define MMC_MEMSIZ1_ROMSW_SHIFT (6) /* Bits 6-7: Allocated System RAM Memory Space */ +# define MMC_MEMSIZ1_ROMSW_MASK (3 << MMC_MEMSIZ1_ROMSW_SHIFT) +# define MEMSIZ1_ROMSW_0KB (0 << MMC_MEMSIZ1_ROMSW_SHIFT) +# define MEMSIZ1_ROMSW_16KB (1 << MMC_MEMSIZ1_ROMSW_SHIFT) +# 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 MMC_PPAGE_PIX_SHIFT (0) /* Bits 0-5 Program Page Index Bits 5–0 */ +# define MMC_PPAGE_PIX_MASK (0x3f << MMC_PPAGE_PIX_SHIFT) + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_HC_SRC_MC9S12NE64_MC9S12NE64_MMC_H */ diff --git a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S index 5f5830e2b..a818a68c2 100755 --- a/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S +++ b/nuttx/arch/hc/src/mc9s12ne64/mc9s12ne64_start.S @@ -2,22 +2,22 @@ * arch/hc/src/mc9s12ne64/mc9s12ne64_start.S * arch/hc/src/chip/mc9s12ne64_start.S * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt * * 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. + * 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. + * 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. + * 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 @@ -41,6 +41,9 @@ #include #include +#include "mc9s12ne64_mmc.h" +#include "mc9s12ne64_crg.h" + /**************************************************************************** * Private Definitions ****************************************************************************/ @@ -52,6 +55,50 @@ .globl __start .file "mc9s12ne64_start.S" +/**************************************************************************** + * Macros + ****************************************************************************/ + +/* Memory map initialization */ + + .macro MMCINIT + movb #0, HC12_MMC_INITRG /* Set the register map position */ + 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 */ + .endm + +/* System clock initialization */ + + .macro PLLINIT + + /* Select the clock source from crystal */ + + movb #0, HC12_CRG_CLKSEL + movb #CRG_CRGSEL_PLLSEL, 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 + + /* 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 + + /* The select the PLL clock source */ + + bset HC12_CRG_CLKSEL_OFFSET, #CRG_CLKSEL_PLLSEL + .endm + /**************************************************************************** * .text ****************************************************************************/ @@ -60,9 +107,11 @@ * Name: __start * * Description: - * Power-up reset entry point + * Power-up reset entry point * ****************************************************************************/ __start: + MMCINIT /* Initialize the MMC */ + PLLINIT /* Initialize the PLL */ .end -- cgit v1.2.3