summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-08-18 18:16:47 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-08-18 18:16:47 +0000
commitb53a4426e1cf580b32c663500ba1b4bb42cb3fdf (patch)
tree6df68855420ba2ab06385b2c0f3d72c7729d38ab
parentaad68a29984f20c2888f6897c2597d80df6bf8ee (diff)
downloadpx4-nuttx-b53a4426e1cf580b32c663500ba1b4bb42cb3fdf.tar.gz
px4-nuttx-b53a4426e1cf580b32c663500ba1b4bb42cb3fdf.tar.bz2
px4-nuttx-b53a4426e1cf580b32c663500ba1b4bb42cb3fdf.zip
Several important Kinetis build fixes
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3891 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_clockconfig.c753
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_start.c2
-rw-r--r--nuttx/configs/kwikstik-k40/ostest/Make.defs8
-rwxr-xr-xnuttx/configs/kwikstik-k40/ostest/defconfig11
-rwxr-xr-xnuttx/configs/kwikstik-k40/ostest/ld.script46
-rw-r--r--nuttx/configs/twr-k60n512/ostest/Make.defs8
-rwxr-xr-xnuttx/configs/twr-k60n512/ostest/defconfig4
-rwxr-xr-xnuttx/configs/twr-k60n512/ostest/ld.script46
8 files changed, 458 insertions, 420 deletions
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_clockconfig.c b/nuttx/arch/arm/src/kinetis/kinetis_clockconfig.c
index bcb3540d7..f167a0328 100644
--- a/nuttx/arch/arm/src/kinetis/kinetis_clockconfig.c
+++ b/nuttx/arch/arm/src/kinetis/kinetis_clockconfig.c
@@ -1,374 +1,379 @@
-/****************************************************************************
- * arch/arm/src/kinetis/kinetis_clockconfig.c
- * arch/arm/src/chip/kinetis_clockconfig.c
- *
- * Copyright (C) 2011 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 <arch/board/board.h>
-
-#include "up_arch.h"
-
-#include "kinetis_internal.h"
-#include "kinetis_mcg.h"
-#include "kinetis_sim.h"
-#include "kinetis_fmc.h"
-#include "kinetis_llwu.h"
-#include "kinetis_pinmux.h"
-
-/****************************************************************************
- * Private Definitions
- ****************************************************************************/
-
-#ifndef CONFIG_BOOT_RAMFUNCS
-# error "CONFIG_BOOT_RAMFUNCS must be defined for this logic"
-#endif
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-static void __ramfunc__
-kinesis_setdividers(uint32_t div1, uint32_t div2, uint32_t div3, uint32_t div4);
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: kinesis_portclocks
- *
- * Description:
- * Enable all of the port clocks
- *
- ****************************************************************************/
-
-static inline void kinesis_portclocks(void)
-{
- uint32_t regval;
-
- /* Enable all of the port clocks */
-
- regval = getreg32(KINETIS_SIM_SCGC5);
- regval |= (SIM_SCGC5_PORTA | SIM_SCGC5_PORTB | SIM_SCGC5_PORTC |
- SIM_SCGC5_PORTD | SIM_SCGC5_PORTE);
- putreg32(regval, KINETIS_SIM_SCGC5);
-}
-
-/****************************************************************************
- * Name: kinesis_setdividers
- *
- * Description:
- * "This routine must be placed in RAM. It is a workaround for errata e2448.
- * Flash prefetch must be disabled when the flash clock divider is changed.
- * This cannot be performed while executing out of flash. There must be a
- * short delay after the clock dividers are changed before prefetch can be
- * re-enabled."
- *
- ****************************************************************************/
-
-static void __ramfunc__
-kinesis_setdividers(uint32_t div1, uint32_t div2, uint32_t div3, uint32_t div4)
-{
- uint32_t regval;
- int i;
-
- /* Save the current value of the Flash Access Protection Register */
-
- regval = getreg32(KINETIS_FMC_PFAPR);
-
- /* Set M0PFD through M7PFD to 1 to disable prefetch */
-
- putreg32(FMC_PFAPR_M7PFD | FMC_PFAPR_M6PFD | FMC_PFAPR_M5PFD |
- FMC_PFAPR_M4PFD | FMC_PFAPR_M3PFD | FMC_PFAPR_M2PFD |
- FMC_PFAPR_M1PFD | FMC_PFAPR_M0PFD,
- KINETIS_FMC_PFAPR);
-
- /* Set clock dividers to desired value */
-
- putreg32(SIM_CLKDIV1_OUTDIV1(div1) | SIM_CLKDIV1_OUTDIV2(div2) |
- SIM_CLKDIV1_OUTDIV3(div3) | SIM_CLKDIV1_OUTDIV4(div4),
- KINETIS_SIM_CLKDIV1);
-
- /* Wait for dividers to change */
-
- for (i = 0 ; i < div4 ; i++);
-
- /* Re-store the saved value of FMC_PFAPR */
-
- putreg32(regval, KINETIS_FMC_PFAPR);
-}
-
-/****************************************************************************
- * Name: kinetis_pllconfig
- *
- * Description:
- * Initialize the PLL using the settings in board.h. This assumes that
- * the MCG is in default FLL Engaged Internal (FEI mode) out of reset.
- *
- ****************************************************************************/
-
-void kinetis_pllconfig(void)
-{
- uint32_t regval32;
- uint8_t regval8;
-
- /* Transition to FLL Bypassed External (FBE) mode */
-
-#ifdef BOARD_EXTCLOCK
- /* IRCS = 0 (Internal Reference Clock Select)
- * LP = 0 (Low Power Select)
- * EREFS = 0 (External Reference Select)
- * HGO = 0 (High Gain Oscillator Select)
- * RANGE = 0 (Oscillator of 32 kHz to 40 kHz)
- */
-
- putreg8(0, KINETIS_MCG_C2);
-#else
- /* Enable external oscillator:
- *
- * IRCS = 0 (Internal Reference Clock Select)
- * LP = 0 (Low Power Select)
- * EREFS = 1 (External Reference Select)
- * HGO = 1 (High Gain Oscillator Select)
- * RANGE = 2 (Oscillator of 8 MHz to 32 MHz)
- */
-
- putreg8(MCG_C2_EREFS | MCG_C2_HGO | MCG_C2_RANGE_VHIGH, KINETIS_MCG_C2);
-#endif
-
- /* Released latched state of oscillator and GPIO */
-
- regval32 = getreg32(KINETIS_SIM_SCGC4);
- regval32 |= SIM_SCGC4_LLWU;
- putreg32(regval32, KINETIS_SIM_SCGC4);
-
- regval8 = getreg8(KINETIS_LLWU_CS);
- regval8 |= LLWU_CS_ACKISO;
- putreg8(regval8, KINETIS_LLWU_CS);
-
- /* Select external oscillator and Reference Divider and clear IREFS to
- * start the external oscillator.
- *
- * IREFSTEN = 0 (Internal Reference Stop Enable)
- * IRCLKEN = 0 (Internal Reference Clock Enable)
- * IREFS = 0 (Internal Reference Select)
- * FRDIV = 3 (FLL External Reference Divider, RANGE!=0 divider=256)
- * CLKS = 2 (Clock Source Select, External reference clock)
- */
-
- putreg8(MCG_C1_FRDIV_DIV256 | MCG_C1_CLKS_EXTREF, KINETIS_MCG_C1);
-
- /* If we aren't using an oscillator input we don't need to wait for the
- * oscillator to initialize
- */
-
-#ifndef BOARD_EXTCLOCK
- while ((getreg8(KINETIS_MCG_S) & MCG_S_OSCINIT) == 0);
-#endif
-
- /* Wait for Reference clock Status bit to clear */
-
- while ((getreg8(KINETIS_MCG_S) & MCG_S_IREFST) != 0);
-
- /* Wait for clock status bits to show that the clock source is the
- * external reference clock.
- */
-
- while ((getreg8(KINETIS_MCG_S) & MCG_S_CLKST_MASK) != MCG_S_CLKST_EXTREF);
-
- /* We are now in FLL Bypassed External (FBE) mode. Configure PLL
- * reference clock divider:
- *
- * PLLCLKEN = 0
- * PLLSTEN = 0
- * PRDIV = Determined by PLL reference clock frequency
- *
- * Either the external clock or crystal frequency is used to select the
- * PRDIV value. Only reference clock frequencies are supported that will
- * produce a 2MHz reference clock to the PLL.
- */
-
- putreg8(MCG_C5_PRDIV(BOARD_PRDIV), KINETIS_MCG_C5);
-
- /* Ensure that MCG_C6 is at the reset default of 0: LOLIE disabled, PLL
- * disabled, clk monitor disabled, PLL VCO divider cleared.
- */
-
- putreg8(0, KINETIS_MCG_C6);
-
- /* Set system options dividers based on settings from the board.h file.
- *
- * MCG = PLL
- * Core = MCG / BOARD_OUTDIV1
- * bus = MCG / BOARD_OUTDIV1
- * FlexBus = MCG / BOARD_OUTDIV1
- * Flash clock = MCG/2 / BOARD_OUTDIV1
- */
-
- kinesis_setdividers(BOARD_OUTDIV1, BOARD_OUTDIV2, BOARD_OUTDIV3, BOARD_OUTDIV4);
-
- /* Set the VCO divider, VDIV, is defined in the board.h file. VDIV
- * selects the amount to divide the VCO output of the PLL. The VDIV bits
- * establish the multiplication factor applied to the reference clock
- * frequency. Also set
- *
- * LOLIE = 0 (Loss of Lock Interrrupt Enable)
- * PLLS = 1 (PLL Select)
- * CME = 0 (Clock Monitor Enable)
- */
-
- putreg8(MCG_C6_PLLS | MCG_C6_VDIV(BOARD_VDIV), KINETIS_MCG_C6);
-
- /* Wait for the PLL status bit to set */
-
- while ((getreg8(KINETIS_MCG_S) & MCG_S_PLLST) == 0);
-
- /* Wait for the PLL LOCK bit to set */
-
- while ((getreg8(KINETIS_MCG_S) & MCG_S_LOCK) == 0);
-
- /* We are now running in PLL Bypassed External (PBE) mode. Transition to
- * PLL Engaged External (PEE) mode by setting CLKS to 0
- */
-
- regval8 = getreg8(KINETIS_MCG_C1);
- regval8 &= ~MCG_C1_CLKS_MASK;
- putreg8(regval8, KINETIS_MCG_C1);
-
- /* Wait for clock status bits to update */
-
- while ((getreg8(KINETIS_MCG_S) & MCG_S_CLKST_MASK) != MCG_S_CLKST_PLL);
-
- /* We are now running in PLL Engaged External (PEE) mode. */
-}
-
-/****************************************************************************
- * Name: kinetis_traceconfig
- *
- * Description:
- * Enable trace clocks.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_KINETIS_TRACE
-static inline void kinetis_traceconfig(void)
-{
- uint32_t regval;
-
- /* Set the trace clock to the core clock frequency in the SIM SOPT2 register */
-
- regval = getreg32(KINETIS_SIM_SOPT2);
- regval |= SIM_SOPT2_TRACECLKSEL;
- putreg32(regval, KINETIS_SIM_SOPT2);
-
- /* Enable the TRACE_CLKOUT pin function on the configured pin */
-
- kinetis_gpioconfig(GPIO_TRACE_CLKOUT);
-}
-#else
-# define kinetis_traceconfig()
-#endif
-
-/****************************************************************************
- * Name: kinetis_fbconfig
- *
- * Description:
- * Enable FlexBus clocking.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_KINETIS_FLEXBUS
-static inline void kinetis_fbconfig(void)
-{
- uint32_t regval;
-
- /* Enable the clock to the FlexBus module */
-
- regval = getreg32(KINETIS_SIM_SCGC7);
- regval |= SIM_SCGC7_FLEXBUS;
- putreg32(regval, KINETIS_SIM_SCGC7);
-
- /* Enable the FB_CLKOUT function on PTC3 (alt5 function) */
-
- kinetis_gpioconfig(GPIO_FB_CLKOUT);
-}
-#else
-# define kinetis_fbconfig()
-#endif
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: kinetis_clockconfig
- *
- * Description:
- * Called to initialize the Kinetis chip. This does whatever setup is
- * needed to put the MCU in a usable state. This includes the
- * initialization of clocking using the settings in board.h.
- *
- ****************************************************************************/
-
-void kinetis_clockconfig(void)
-{
- /* Enable all of the port clocks */
-
- kinesis_portclocks();
-
- /* Configure the PLL based on settings in the board.h file */
-
- kinetis_pllconfig();
-
- /* For debugging, we will normally want to enable the trace clock and/or
- * the FlexBus clock.
- */
-
- kinetis_traceconfig();
- kinetis_fbconfig();
-}
-
+/****************************************************************************
+ * arch/arm/src/kinetis/kinetis_clockconfig.c
+ * arch/arm/src/chip/kinetis_clockconfig.c
+ *
+ * Copyright (C) 2011 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 <arch/board/board.h>
+
+#include "up_arch.h"
+
+#include "kinetis_internal.h"
+#include "kinetis_mcg.h"
+#include "kinetis_sim.h"
+#include "kinetis_fmc.h"
+#include "kinetis_llwu.h"
+#include "kinetis_pinmux.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+#ifndef CONFIG_BOOT_RAMFUNCS
+# error "CONFIG_BOOT_RAMFUNCS must be defined for this logic"
+#endif
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+void __ramfunc__
+kinesis_setdividers(uint32_t div1, uint32_t div2, uint32_t div3, uint32_t div4);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kinesis_portclocks
+ *
+ * Description:
+ * Enable all of the port clocks
+ *
+ ****************************************************************************/
+
+static inline void kinesis_portclocks(void)
+{
+ uint32_t regval;
+
+ /* Enable all of the port clocks */
+
+ regval = getreg32(KINETIS_SIM_SCGC5);
+ regval |= (SIM_SCGC5_PORTA | SIM_SCGC5_PORTB | SIM_SCGC5_PORTC |
+ SIM_SCGC5_PORTD | SIM_SCGC5_PORTE);
+ putreg32(regval, KINETIS_SIM_SCGC5);
+}
+
+/****************************************************************************
+ * Name: kinetis_pllconfig
+ *
+ * Description:
+ * Initialize the PLL using the settings in board.h. This assumes that
+ * the MCG is in default FLL Engaged Internal (FEI mode) out of reset.
+ *
+ ****************************************************************************/
+
+void kinetis_pllconfig(void)
+{
+ uint32_t regval32;
+ uint8_t regval8;
+
+ /* Transition to FLL Bypassed External (FBE) mode */
+
+#ifdef BOARD_EXTCLOCK
+ /* IRCS = 0 (Internal Reference Clock Select)
+ * LP = 0 (Low Power Select)
+ * EREFS = 0 (External Reference Select)
+ * HGO = 0 (High Gain Oscillator Select)
+ * RANGE = 0 (Oscillator of 32 kHz to 40 kHz)
+ */
+
+ putreg8(0, KINETIS_MCG_C2);
+#else
+ /* Enable external oscillator:
+ *
+ * IRCS = 0 (Internal Reference Clock Select)
+ * LP = 0 (Low Power Select)
+ * EREFS = 1 (External Reference Select)
+ * HGO = 1 (High Gain Oscillator Select)
+ * RANGE = 2 (Oscillator of 8 MHz to 32 MHz)
+ */
+
+ putreg8(MCG_C2_EREFS | MCG_C2_HGO | MCG_C2_RANGE_VHIGH, KINETIS_MCG_C2);
+#endif
+
+ /* Released latched state of oscillator and GPIO */
+
+ regval32 = getreg32(KINETIS_SIM_SCGC4);
+ regval32 |= SIM_SCGC4_LLWU;
+ putreg32(regval32, KINETIS_SIM_SCGC4);
+
+ regval8 = getreg8(KINETIS_LLWU_CS);
+ regval8 |= LLWU_CS_ACKISO;
+ putreg8(regval8, KINETIS_LLWU_CS);
+
+ /* Select external oscillator and Reference Divider and clear IREFS to
+ * start the external oscillator.
+ *
+ * IREFSTEN = 0 (Internal Reference Stop Enable)
+ * IRCLKEN = 0 (Internal Reference Clock Enable)
+ * IREFS = 0 (Internal Reference Select)
+ * FRDIV = 3 (FLL External Reference Divider, RANGE!=0 divider=256)
+ * CLKS = 2 (Clock Source Select, External reference clock)
+ */
+
+ putreg8(MCG_C1_FRDIV_DIV256 | MCG_C1_CLKS_EXTREF, KINETIS_MCG_C1);
+
+ /* If we aren't using an oscillator input we don't need to wait for the
+ * oscillator to initialize
+ */
+
+#ifndef BOARD_EXTCLOCK
+ while ((getreg8(KINETIS_MCG_S) & MCG_S_OSCINIT) == 0);
+#endif
+
+ /* Wait for Reference clock Status bit to clear */
+
+ while ((getreg8(KINETIS_MCG_S) & MCG_S_IREFST) != 0);
+
+ /* Wait for clock status bits to show that the clock source is the
+ * external reference clock.
+ */
+
+ while ((getreg8(KINETIS_MCG_S) & MCG_S_CLKST_MASK) != MCG_S_CLKST_EXTREF);
+
+ /* We are now in FLL Bypassed External (FBE) mode. Configure PLL
+ * reference clock divider:
+ *
+ * PLLCLKEN = 0
+ * PLLSTEN = 0
+ * PRDIV = Determined by PLL reference clock frequency
+ *
+ * Either the external clock or crystal frequency is used to select the
+ * PRDIV value. Only reference clock frequencies are supported that will
+ * produce a 2MHz reference clock to the PLL.
+ */
+
+ putreg8(MCG_C5_PRDIV(BOARD_PRDIV), KINETIS_MCG_C5);
+
+ /* Ensure that MCG_C6 is at the reset default of 0: LOLIE disabled, PLL
+ * disabled, clk monitor disabled, PLL VCO divider cleared.
+ */
+
+ putreg8(0, KINETIS_MCG_C6);
+
+ /* Set system options dividers based on settings from the board.h file.
+ *
+ * MCG = PLL
+ * Core = MCG / BOARD_OUTDIV1
+ * bus = MCG / BOARD_OUTDIV2
+ * FlexBus = MCG / BOARD_OUTDIV3
+ * Flash clock = MCG / BOARD_OUTDIV4
+ */
+
+ kinesis_setdividers(BOARD_OUTDIV1, BOARD_OUTDIV2, BOARD_OUTDIV3, BOARD_OUTDIV4);
+
+ /* Set the VCO divider, VDIV, is defined in the board.h file. VDIV
+ * selects the amount to divide the VCO output of the PLL. The VDIV bits
+ * establish the multiplication factor applied to the reference clock
+ * frequency. Also set
+ *
+ * LOLIE = 0 (Loss of Lock Interrrupt Enable)
+ * PLLS = 1 (PLL Select)
+ * CME = 0 (Clock Monitor Enable)
+ */
+
+ putreg8(MCG_C6_PLLS | MCG_C6_VDIV(BOARD_VDIV), KINETIS_MCG_C6);
+
+ /* Wait for the PLL status bit to set */
+
+ while ((getreg8(KINETIS_MCG_S) & MCG_S_PLLST) == 0);
+
+ /* Wait for the PLL LOCK bit to set */
+
+ while ((getreg8(KINETIS_MCG_S) & MCG_S_LOCK) == 0);
+
+ /* We are now running in PLL Bypassed External (PBE) mode. Transition to
+ * PLL Engaged External (PEE) mode by setting CLKS to 0
+ */
+
+ regval8 = getreg8(KINETIS_MCG_C1);
+ regval8 &= ~MCG_C1_CLKS_MASK;
+ putreg8(regval8, KINETIS_MCG_C1);
+
+ /* Wait for clock status bits to update */
+
+ while ((getreg8(KINETIS_MCG_S) & MCG_S_CLKST_MASK) != MCG_S_CLKST_PLL);
+
+ /* We are now running in PLL Engaged External (PEE) mode. */
+}
+
+/****************************************************************************
+ * Name: kinetis_traceconfig
+ *
+ * Description:
+ * Enable trace clocks.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KINETIS_TRACE
+static inline void kinetis_traceconfig(void)
+{
+ uint32_t regval;
+
+ /* Set the trace clock to the core clock frequency in the SIM SOPT2 register */
+
+ regval = getreg32(KINETIS_SIM_SOPT2);
+ regval |= SIM_SOPT2_TRACECLKSEL;
+ putreg32(regval, KINETIS_SIM_SOPT2);
+
+ /* Enable the TRACE_CLKOUT pin function on the configured pin */
+
+ kinetis_gpioconfig(GPIO_TRACE_CLKOUT);
+}
+#else
+# define kinetis_traceconfig()
+#endif
+
+/****************************************************************************
+ * Name: kinetis_fbconfig
+ *
+ * Description:
+ * Enable FlexBus clocking.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KINETIS_FLEXBUS
+static inline void kinetis_fbconfig(void)
+{
+ uint32_t regval;
+
+ /* Enable the clock to the FlexBus module */
+
+ regval = getreg32(KINETIS_SIM_SCGC7);
+ regval |= SIM_SCGC7_FLEXBUS;
+ putreg32(regval, KINETIS_SIM_SCGC7);
+
+ /* Enable the FB_CLKOUT function on PTC3 (alt5 function) */
+
+ kinetis_gpioconfig(GPIO_FB_CLKOUT);
+}
+#else
+# define kinetis_fbconfig()
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: kinetis_clockconfig
+ *
+ * Description:
+ * Called to initialize the Kinetis chip. This does whatever setup is
+ * needed to put the MCU in a usable state. This includes the
+ * initialization of clocking using the settings in board.h.
+ *
+ ****************************************************************************/
+
+void kinetis_clockconfig(void)
+{
+ /* Enable all of the port clocks */
+
+ kinesis_portclocks();
+
+ /* Configure the PLL based on settings in the board.h file */
+
+ kinetis_pllconfig();
+
+ /* For debugging, we will normally want to enable the trace clock and/or
+ * the FlexBus clock.
+ */
+
+ kinetis_traceconfig();
+ kinetis_fbconfig();
+}
+
+/****************************************************************************
+ * Name: kinesis_setdividers
+ *
+ * Description:
+ * "This routine must be placed in RAM. It is a workaround for errata e2448.
+ * Flash prefetch must be disabled when the flash clock divider is changed.
+ * This cannot be performed while executing out of flash. There must be a
+ * short delay after the clock dividers are changed before prefetch can be
+ * re-enabled."
+ *
+ * NOTE: This must have global scope only to prevent optimization logic from
+ * inlining the function.
+ *
+ ****************************************************************************/
+
+void __ramfunc__
+kinesis_setdividers(uint32_t div1, uint32_t div2, uint32_t div3, uint32_t div4)
+{
+ uint32_t regval;
+ int i;
+
+ /* Save the current value of the Flash Access Protection Register */
+
+ regval = getreg32(KINETIS_FMC_PFAPR);
+
+ /* Set M0PFD through M7PFD to 1 to disable prefetch */
+
+ putreg32(FMC_PFAPR_M7PFD | FMC_PFAPR_M6PFD | FMC_PFAPR_M5PFD |
+ FMC_PFAPR_M4PFD | FMC_PFAPR_M3PFD | FMC_PFAPR_M2PFD |
+ FMC_PFAPR_M1PFD | FMC_PFAPR_M0PFD,
+ KINETIS_FMC_PFAPR);
+
+ /* Set clock dividers to desired value */
+
+ putreg32(SIM_CLKDIV1_OUTDIV1(div1) | SIM_CLKDIV1_OUTDIV2(div2) |
+ SIM_CLKDIV1_OUTDIV3(div3) | SIM_CLKDIV1_OUTDIV4(div4),
+ KINETIS_SIM_CLKDIV1);
+
+ /* Wait for dividers to change */
+
+ for (i = 0 ; i < div4 ; i++);
+
+ /* Re-store the saved value of FMC_PFAPR */
+
+ putreg32(regval, KINETIS_FMC_PFAPR);
+}
+
+
+
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_start.c b/nuttx/arch/arm/src/kinetis/kinetis_start.c
index d976e5b2c..1ebb894e1 100644
--- a/nuttx/arch/arm/src/kinetis/kinetis_start.c
+++ b/nuttx/arch/arm/src/kinetis/kinetis_start.c
@@ -116,7 +116,7 @@ void __start(void)
* at _framfuncs
*/
-#ifndef CONFIG_BOOT_RAMFUNCS
+#ifdef CONFIG_BOOT_RAMFUNCS
for (src = &_framfuncs, dest = &_sramfuncs; dest < &_eramfuncs; )
{
*dest++ = *src++;
diff --git a/nuttx/configs/kwikstik-k40/ostest/Make.defs b/nuttx/configs/kwikstik-k40/ostest/Make.defs
index 6259f67cb..ef478d80a 100644
--- a/nuttx/configs/kwikstik-k40/ostest/Make.defs
+++ b/nuttx/configs/kwikstik-k40/ostest/Make.defs
@@ -41,24 +41,24 @@ ifeq ($(CONFIG_KINETIS_CODESOURCERYW),y)
# CodeSourcery under Windows
CROSSDEV = arm-none-eabi-
WINTOOL = y
- ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls
endif
ifeq ($(CONFIG_KINETIS_CODESOURCERYL),y)
# CodeSourcery under Linux
CROSSDEV = arm-none-eabi-
- ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls
MAXOPTIMIZATION = -O2
endif
ifeq ($(CONFIG_KINETIS_DEVKITARM),y)
# devkitARM under Windows
CROSSDEV = arm-eabi-
WINTOOL = y
- ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls
endif
ifeq ($(CONFIG_KINETIS_BUILDROOT),y)
# NuttX buildroot under Linux or Cygwin
CROSSDEV = arm-elf-
- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
+ ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft -mlong-calls
MAXOPTIMIZATION = -Os
endif
diff --git a/nuttx/configs/kwikstik-k40/ostest/defconfig b/nuttx/configs/kwikstik-k40/ostest/defconfig
index 9cf3af7f6..833511a87 100755
--- a/nuttx/configs/kwikstik-k40/ostest/defconfig
+++ b/nuttx/configs/kwikstik-k40/ostest/defconfig
@@ -77,15 +77,8 @@ CONFIG_ARCH_CHIP_MK40X256VLQ100=y
CONFIG_ARCH_BOARD=kwikstik-k40
CONFIG_ARCH_BOARD_KWIKSTIK_K40=y
CONFIG_BOARD_LOOPSPERMSEC=5483
-CONFIG_DRAM_SIZE=0x18000000
-CONFIG_DRAM_START=0x00008000
-
-# define KINETIS_SRAML_BASE 0x18000000 /* –0x1fffffff SRAM_L: Lower SRAM
-
-# define KINETIS_FLASH_SIZE (256*1024) /* 256Kb */
-# define KINETIS_FLEXMEM_SIZE (256*1024) /* 256Kb */
-# define KINETIS_SRAM_SIZE (64*1024) /* 32Kb */
-
+CONFIG_DRAM_START=0x1fff8000
+CONFIG_DRAM_SIZE= 0x00010000
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
diff --git a/nuttx/configs/kwikstik-k40/ostest/ld.script b/nuttx/configs/kwikstik-k40/ostest/ld.script
index edadb38a0..f4f3f2e69 100755
--- a/nuttx/configs/kwikstik-k40/ostest/ld.script
+++ b/nuttx/configs/kwikstik-k40/ostest/ld.script
@@ -34,22 +34,42 @@
****************************************************************************/
/* The K40X256VLQ100 has 256Kb of FLASH beginning at address 0x0000:0000 and
- * 32Kb of SRAM beginning at address 0x1800:0000.
+ * 64Kb of SRAM beginning at address 0x1800:0000 (SRAM_L) and 0x2000:000
+ * (SRAM_U).
+ *
+ * NOTE: that the first part of the K40 FLASH region is reserved for
+ * interrupt vectflash and, following that, is a region from 0x0000:0400
+ * to 0x0000:040f that is reserved for the FLASH control fields (FCF).
+ *
+ * NOTE: The on-chip RAM is split evenly among SRAM_L and SRAM_U. The RAM is
+ * also implemented such that the SRAM_L and SRAM_U ranges form a
+ * contiguous block in the memory map.
*/
MEMORY
{
- flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
- sram (rwx) : ORIGIN = 0x18000000, LENGTH = 32K
+ vectflash (rx) : ORIGIN = 0x00000000, LENGTH = 1K - 16
+ cfmprotect (rx) : ORIGIN = 0x00000400, LENGTH = 16
+ progflash (rx) : ORIGIN = 0x00000800, LENGTH = 256K - 2K
+ datasram (rwx) : ORIGIN = 0x1fff8000, LENGTH = 64K
}
OUTPUT_ARCH(arm)
ENTRY(_stext)
SECTIONS
{
+ .vectors : {
+ _svectors = ABSOLUTE(.);
+ *(.vectors)
+ _evectors = ABSOLUTE(.);
+ } > vectflash
+
+ .cfmprotect : {
+ *(.cfmconfig)
+ } > cfmprotect
+
.text : {
_stext = ABSOLUTE(.);
- *(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
@@ -61,7 +81,7 @@ SECTIONS
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
- } > flash
+ } > progflash
.data : {
_sdata = ABSOLUTE(.);
@@ -69,26 +89,26 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
- } > sram AT > flash
+ } > datasram AT > progflash
_eronly = LOADADDR(.data);
.ramfunc ALIGN(4): {
- _sramfunc_begin = . ;
+ _sramfuncs = ABSOLUTE(.);
*(.ramfunc .ramfunc.*)
- _eramfunc_end = . ;
- } > sram AT > flash
+ _eramfuncs = ABSOLUTE(.);
+ } > datasram AT > progflash
- _framfunc = LOADADDR(.ramfunc);
+ _framfuncs = LOADADDR(.ramfunc);
.ARM.extab : {
*(.ARM.extab*)
- } >sram
+ } > datasram
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
- } >sram
+ } > datasram
__exidx_end = ABSOLUTE(.);
.bss : {
@@ -97,7 +117,7 @@ SECTIONS
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
- } > sram
+ } > datasram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
diff --git a/nuttx/configs/twr-k60n512/ostest/Make.defs b/nuttx/configs/twr-k60n512/ostest/Make.defs
index 76e942b40..5299bbd54 100644
--- a/nuttx/configs/twr-k60n512/ostest/Make.defs
+++ b/nuttx/configs/twr-k60n512/ostest/Make.defs
@@ -41,24 +41,24 @@ ifeq ($(CONFIG_KINETIS_CODESOURCERYW),y)
# CodeSourcery under Windows
CROSSDEV = arm-none-eabi-
WINTOOL = y
- ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls
endif
ifeq ($(CONFIG_KINETIS_CODESOURCERYL),y)
# CodeSourcery under Linux
CROSSDEV = arm-none-eabi-
- ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls
MAXOPTIMIZATION = -O2
endif
ifeq ($(CONFIG_KINETIS_DEVKITARM),y)
# devkitARM under Windows
CROSSDEV = arm-eabi-
WINTOOL = y
- ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft -mlong-calls
endif
ifeq ($(CONFIG_KINETIS_BUILDROOT),y)
# NuttX buildroot under Linux or Cygwin
CROSSDEV = arm-elf-
- ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
+ ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft -mlong-calls
MAXOPTIMIZATION = -Os
endif
diff --git a/nuttx/configs/twr-k60n512/ostest/defconfig b/nuttx/configs/twr-k60n512/ostest/defconfig
index 94ef1e82f..9770e91ca 100755
--- a/nuttx/configs/twr-k60n512/ostest/defconfig
+++ b/nuttx/configs/twr-k60n512/ostest/defconfig
@@ -77,8 +77,8 @@ CONFIG_ARCH_CHIP_MK60N512VMD100=y
CONFIG_ARCH_BOARD=twr-k60n512
CONFIG_ARCH_BOARD_TWR_K60N512=y
CONFIG_BOARD_LOOPSPERMSEC=5483
-CONFIG_DRAM_SIZE=0x18000000
-CONFIG_DRAM_START=0x00020000
+CONFIG_DRAM_START=0x1fff0000
+CONFIG_DRAM_SIZE=0x00020000
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
diff --git a/nuttx/configs/twr-k60n512/ostest/ld.script b/nuttx/configs/twr-k60n512/ostest/ld.script
index a9172e569..d7692e1d3 100755
--- a/nuttx/configs/twr-k60n512/ostest/ld.script
+++ b/nuttx/configs/twr-k60n512/ostest/ld.script
@@ -34,22 +34,42 @@
****************************************************************************/
/* The K60N512VMD100 has 512Kb of FLASH beginning at address 0x0000:0000 and
- * 128Kb of SRAM beginning at address 0x1800:0000.
+ * 128Kb of SRAM beginning at address 0x1800:0000 (SRAM_L) and 0x2000:000
+ * (SRAM_U).
+ *
+ * NOTE: that the first part of the K40 FLASH region is reserved for
+ * interrupt vectflash and, following that, is a region from 0x0000:0400
+ * to 0x0000:040f that is reserved for the FLASH control fields (FCF).
+ *
+ * NOTE: The on-chip RAM is split evenly among SRAM_L and SRAM_U. The RAM is
+ * also implemented such that the SRAM_L and SRAM_U ranges form a
+ * contiguous block in the memory map.
*/
MEMORY
{
- flash (rx) : ORIGIN = 0x00000000, LENGTH = 512K
- sram (rwx) : ORIGIN = 0x18000000, LENGTH = 128K
+ vectflash (rx) : ORIGIN = 0x00000000, LENGTH = 1K - 16
+ cfmprotect (rx) : ORIGIN = 0x00000400, LENGTH = 16
+ progflash (rx) : ORIGIN = 0x00000800, LENGTH = 512K - 2K
+ datasram (rwx) : ORIGIN = 0x1fff0000, LENGTH = 128K
}
OUTPUT_ARCH(arm)
ENTRY(_stext)
SECTIONS
{
+ .vectors : {
+ _svectors = ABSOLUTE(.);
+ *(.vectors)
+ _evectors = ABSOLUTE(.);
+ } > vectflash
+
+ .cfmprotect : {
+ *(.cfmconfig)
+ } > cfmprotect
+
.text : {
_stext = ABSOLUTE(.);
- *(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
@@ -61,7 +81,7 @@ SECTIONS
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
- } > flash
+ } > progflash
.data : {
_sdata = ABSOLUTE(.);
@@ -69,26 +89,26 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
- } > sram AT > flash
+ } > datasram AT > progflash
_eronly = LOADADDR(.data);
.ramfunc ALIGN(4): {
- _sramfunc_begin = . ;
+ _sramfuncs = ABSOLUTE(.);
*(.ramfunc .ramfunc.*)
- _eramfunc_end = . ;
- } > sram AT > flash
+ _eramfuncs = ABSOLUTE(.);
+ } > datasram AT > progflash
- _framfunc = LOADADDR(.ramfunc);
+ _framfuncs = LOADADDR(.ramfunc);
.ARM.extab : {
*(.ARM.extab*)
- } >sram
+ } > datasram
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
- } >sram
+ } > datasram
__exidx_end = ABSOLUTE(.);
.bss : {
@@ -97,7 +117,7 @@ SECTIONS
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
- } > sram
+ } > datasram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }