summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-22 15:12:50 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-22 15:12:50 +0000
commit273a2b0d87cc6bde28cbae477afc313f017b4d3a (patch)
tree1a9237dab9454102679fad0b6b1570ee271f4986
parentb3da63f487b2ccc69afd9610e0a6082d8482df56 (diff)
downloadpx4-nuttx-273a2b0d87cc6bde28cbae477afc313f017b4d3a.tar.gz
px4-nuttx-273a2b0d87cc6bde28cbae477afc313f017b4d3a.tar.bz2
px4-nuttx-273a2b0d87cc6bde28cbae477afc313f017b4d3a.zip
Make the Olimex stm32 p107 clock configuratin the standard for connectivity line devices
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5175 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig4
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c127
-rw-r--r--nuttx/configs/olimex-stm32-p107/include/board.h30
-rw-r--r--nuttx/configs/olimex-stm32-p107/nsh/defconfig1
-rw-r--r--nuttx/configs/olimex-stm32-p107/ostest/defconfig1
-rw-r--r--nuttx/configs/olimex-stm32-p107/src/up_boot.c108
-rw-r--r--nuttx/configs/shenzhou/include/board.h30
-rw-r--r--nuttx/configs/shenzhou/nsh/defconfig2
-rw-r--r--nuttx/configs/shenzhou/src/Makefile4
-rw-r--r--nuttx/configs/shenzhou/src/up_clockconfig.c167
10 files changed, 156 insertions, 318 deletions
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index a0f9a4892..c7dae4460 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -1732,11 +1732,11 @@ config STM32_MII_EXTCLK
endchoice
config STM32_AUTONEG
- bool "Use autonegtiation"
+ bool "Use autonegotiation"
default y
depends on STM32_ETHMAC
---help---
- Use PHY autonegotion to determine speed and mode
+ Use PHY autonegotiation to determine speed and mode
config STM32_ETHFD
bool "Full duplex"
diff --git a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c
index 10b8572cf..47ed5e016 100644
--- a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c
@@ -90,7 +90,7 @@ static inline void rcc_reset(void)
regval = getreg32(STM32_RCC_CR); /* Reset HSEBYP bit */
regval &= ~RCC_CR_HSEBYP;
putreg32(regval, STM32_RCC_CR);
-
+
regval = getreg32(STM32_RCC_CFGR); /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK|RCC_CFGR_USBPRE);
putreg32(regval, STM32_RCC_CFGR);
@@ -235,7 +235,7 @@ static inline void rcc_enableapb1(void)
regval |= RCC_APB1ENR_SPI2EN;
#endif
-
+
#ifdef CONFIG_STM32_SPI3
/* SPI 3 clock enable */
@@ -411,13 +411,128 @@ static inline void rcc_enableapb2(void)
* Name: stm32_stdclockconfig
*
* Description:
- * Called to change to new clock based on settings in board.h
- *
+ * Called to change to new clock based on settings in board.h. This
+ * version is for the Connectivity Line parts.
+ *
+ * NOTE: This logic would need to be extended if you need to select low-
+ * power clocking modes!
+ ****************************************************************************/
+
+#if !defined(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG) && defined(CONFIG_STM32_CONNECTIVITYLINE)
+static void stm32_stdclockconfig(void)
+{
+ uint32_t regval;
+
+ /* Enable HSE */
+
+ regval = getreg32(STM32_RCC_CR);
+ regval &= ~RCC_CR_HSEBYP; /* Disable HSE clock bypass */
+ regval |= RCC_CR_HSEON; /* Enable HSE */
+ putreg32(regval, STM32_RCC_CR);
+
+ /* Set flash wait states
+ * Sysclk runs with 72MHz -> 2 waitstates.
+ * 0WS from 0-24MHz
+ * 1WS from 24-48MHz
+ * 2WS from 48-72MHz
+ */
+
+ regval = getreg32(STM32_FLASH_ACR);
+ regval &= ~FLASH_ACR_LATENCY_MASK;
+ regval |= (FLASH_ACR_LATENCY_2|FLASH_ACR_PRTFBE);
+ putreg32(regval, STM32_FLASH_ACR);
+
+ /* Set up PLL input scaling (with source = PLL2) */
+
+ regval = getreg32(STM32_RCC_CFGR2);
+ regval &= ~(RCC_CFGR2_PREDIV2_MASK | RCC_CFGR2_PLL2MUL_MASK |
+ RCC_CFGR2_PREDIV1SRC_MASK | RCC_CFGR2_PREDIV1_MASK);
+ regval |= (STM32_PLL_PREDIV2 | STM32_PLL_PLL2MUL |
+ RCC_CFGR2_PREDIV1SRC_PLL2 | STM32_PLL_PREDIV1);
+ putreg32(regval, STM32_RCC_CFGR2);
+
+ /* Set the PCLK2 divider */
+
+ regval = getreg32(STM32_RCC_CFGR);
+ regval &= ~(RCC_CFGR_PPRE2_MASK | RCC_CFGR_HPRE_MASK);
+ regval |= STM32_RCC_CFGR_PPRE2;
+ regval |= RCC_CFGR_HPRE_SYSCLK;
+ putreg32(regval, STM32_RCC_CFGR);
+
+ /* Set the PCLK1 divider */
+
+ regval = getreg32(STM32_RCC_CFGR);
+ regval &= ~RCC_CFGR_PPRE1_MASK;
+ regval |= STM32_RCC_CFGR_PPRE1;
+ putreg32(regval, STM32_RCC_CFGR);
+
+ /* Enable PLL2 */
+
+ regval = getreg32(STM32_RCC_CR);
+ regval |= RCC_CR_PLL2ON;
+ putreg32(regval, STM32_RCC_CR);
+
+ /* Wait for PLL2 ready */
+
+ while((getreg32(STM32_RCC_CR) & RCC_CR_PLL2RDY) == 0);
+
+ /* Setup PLL3 for MII/RMII clock on MCO */
+
+#if defined(CONFIG_STM32_MII_MCO) || defined(CONFIG_STM32_RMII_MCO)
+ regval = getreg32(STM32_RCC_CFGR2);
+ regval &= ~(RCC_CFGR2_PLL3MUL_MASK);
+ regval |= STM32_PLL_PLL3MUL;
+ putreg32(regval, STM32_RCC_CFGR2);
+
+ /* Switch PLL3 on */
+
+ regval = getreg32(STM32_RCC_CR);
+ regval |= RCC_CR_PLL3ON;
+ putreg32(regval, STM32_RCC_CR);
+
+ while ((getreg32(STM32_RCC_CR) & RCC_CR_PLL3RDY) == 0);
+#endif
+
+ /* Set main PLL source and multiplier */
+
+ regval = getreg32(STM32_RCC_CFGR);
+ regval &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL_MASK);
+ regval |= (RCC_CFGR_PLLSRC | STM32_PLL_PLLMUL);
+ putreg32(regval, STM32_RCC_CFGR);
+
+ /* Switch main PLL on */
+
+ regval = getreg32(STM32_RCC_CR);
+ regval |= RCC_CR_PLLON;
+ putreg32(regval, STM32_RCC_CR);
+
+ while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLRDY) == 0);
+
+ /* Select PLL as system clock source */
+
+ regval = getreg32(STM32_RCC_CFGR);
+ regval &= ~RCC_CFGR_SW_MASK;
+ regval |= RCC_CFGR_SW_PLL;
+ putreg32(regval, STM32_RCC_CFGR);
+
+ /* Wait until PLL is used as the system clock source */
+
+ while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_PLL) == 0);
+}
+#endif
+
+/****************************************************************************
+ * Name: stm32_stdclockconfig
+ *
+ * Description:
+ * Called to change to new clock based on settings in board.h. This
+ * version is for the non-Connectivity Line parts.
+ *
* NOTE: This logic would need to be extended if you need to select low-
* power clocking modes!
****************************************************************************/
-#ifndef CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG
+#if !defined(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG) && !defined(CONFIG_STM32_CONNECTIVITYLINE)
static void stm32_stdclockconfig(void)
{
uint32_t regval;
@@ -430,7 +545,7 @@ static void stm32_stdclockconfig(void)
volatile int32_t timeout;
/* Enable External High-Speed Clock (HSE) */
-
+
regval = getreg32(STM32_RCC_CR);
regval &= ~RCC_CR_HSEBYP; /* Disable HSE clock bypass */
regval |= RCC_CR_HSEON; /* Enable HSE */
diff --git a/nuttx/configs/olimex-stm32-p107/include/board.h b/nuttx/configs/olimex-stm32-p107/include/board.h
index 2fe6e5aaf..d531eb112 100644
--- a/nuttx/configs/olimex-stm32-p107/include/board.h
+++ b/nuttx/configs/olimex-stm32-p107/include/board.h
@@ -57,9 +57,18 @@
/* On-board crystal frequency is 25MHz (HSE) */
#define STM32_BOARD_XTAL 25000000ul
+
+/* PLL ouput is 72MHz */
+
+#define STM32_PLL_PREDIV2 RCC_CFGR2_PREDIV2d5 /* 25MHz / 5 => 5MHz */
+#define STM32_PLL_PLL2MUL RCC_CFGR2_PLL2MULx8 /* 5MHz * 8 => 40MHz */
+#define STM32_PLL_PREDIV1 RCC_CFGR2_PREDIV1d5 /* 40MHz / 5 => 8MHz */
+#define STM32_PLL_PLLMUL RCC_CFGR_PLLMUL_CLKx9 /* 8MHz * 9 => 72Mhz */
#define STM32_PLL_FREQUENCY (72000000)
-#define STM32_SYSCLK_FREQUENCY STM32_PLL_FREQUENCY
+/* SYCLLK and HCLK are the PLL frequency */
+
+#define STM32_SYSCLK_FREQUENCY STM32_PLL_FREQUENCY
#define STM32_HCLK_FREQUENCY STM32_PLL_FREQUENCY
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
@@ -88,6 +97,12 @@
#define STM32_APB1_TIM6_CLKIN (STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM7_CLKIN (STM32_PCLK1_FREQUENCY)
+/* MCO output */
+
+#if defined(CONFIG_STM32_MII_MCO) || defined(CONFIG_STM32_RMII_MCO)
+# define STM32_PLL_PLL3MUL RCC_CFGR2_PLL3MULx10
+#endif
+
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
@@ -102,16 +117,3 @@
************************************************************************************/
void stm32_boardinitialize(void);
-
-/************************************************************************************
- * Name: stm32_board_clockconfig
- *
- * Description:
- * Any STM32 board may replace the "standard" board clock configuration logic with
- * its own, custom clock cofiguration logic.
- *
- ************************************************************************************/
-
-#ifdef CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG
-void stm32_board_clockconfig(void);
-#endif
diff --git a/nuttx/configs/olimex-stm32-p107/nsh/defconfig b/nuttx/configs/olimex-stm32-p107/nsh/defconfig
index 5c38a49ef..e3fb69ca2 100644
--- a/nuttx/configs/olimex-stm32-p107/nsh/defconfig
+++ b/nuttx/configs/olimex-stm32-p107/nsh/defconfig
@@ -41,7 +41,6 @@ CONFIG_ARCH_CORTEXM3=y
CONFIG_ARCH_CHIP="stm32"
CONFIG_ARCH_CHIP_STM32F107VC=y
CONFIG_ARCH_BOARD="olimex-stm32-p107"
-CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y
CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_START=0x20000000
CONFIG_DRAM_SIZE=65536
diff --git a/nuttx/configs/olimex-stm32-p107/ostest/defconfig b/nuttx/configs/olimex-stm32-p107/ostest/defconfig
index 3710ee95b..36fade11b 100644
--- a/nuttx/configs/olimex-stm32-p107/ostest/defconfig
+++ b/nuttx/configs/olimex-stm32-p107/ostest/defconfig
@@ -41,7 +41,6 @@ CONFIG_ARCH_CORTEXM3=y
CONFIG_ARCH_CHIP="stm32"
CONFIG_ARCH_CHIP_STM32F107VC=y
CONFIG_ARCH_BOARD="olimex-stm32-p107"
-CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y
CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_START=0x20000000
CONFIG_DRAM_SIZE=65536
diff --git a/nuttx/configs/olimex-stm32-p107/src/up_boot.c b/nuttx/configs/olimex-stm32-p107/src/up_boot.c
index d8cba509e..d7ece5a1e 100644
--- a/nuttx/configs/olimex-stm32-p107/src/up_boot.c
+++ b/nuttx/configs/olimex-stm32-p107/src/up_boot.c
@@ -71,111 +71,3 @@
void stm32_boardinitialize(void)
{
}
-
-/************************************************************************************
- * Name: stm32_board_clockconfig
- *
- * Description:
- * Any STM32 board may replace the "standard" board clock configuration logic with
- * its own, custom clock cofiguration logic.
- *
- ************************************************************************************/
-
-#ifdef CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG
-void stm32_board_clockconfig(void)
-{
- uint32_t regval;
-
- regval = getreg32(STM32_RCC_CR);
- regval &= ~RCC_CR_HSEBYP; /* Disable HSE clock bypass */
- regval |= RCC_CR_HSEON; /* Enable HSE */
- putreg32(regval, STM32_RCC_CR);
-
- /* Set flash wait states
- * Sysclk runs with 72MHz -> 2 waitstates.
- * 0WS from 0-24MHz
- * 1WS from 24-48MHz
- * 2WS from 48-72MHz
- */
-
- regval = getreg32(STM32_FLASH_ACR);
- regval &= ~FLASH_ACR_LATENCY_MASK;
- regval |= (FLASH_ACR_LATENCY_2|FLASH_ACR_PRTFBE);
- putreg32(regval, STM32_FLASH_ACR);
-
- regval = getreg32(STM32_RCC_CFGR2);
- regval &= ~(RCC_CFGR2_PREDIV2_MASK
- | RCC_CFGR2_PLL2MUL_MASK
- | RCC_CFGR2_PREDIV1SRC_MASK
- | RCC_CFGR2_PREDIV1_MASK);
- regval |= RCC_CFGR2_PREDIV2d5; /* 25MHz / 5 */
- regval |= RCC_CFGR2_PLL2MULx8; /* 5MHz * 8 => 40MHz */
- regval |= RCC_CFGR2_PREDIV1SRC_PLL2; /* Use PLL2 as input for PREDIV1 */
- regval |= RCC_CFGR2_PREDIV1d5; /* 40MHz / 5 => 8MHz */
- putreg32(regval, STM32_RCC_CFGR2);
-
- /* Set the PCLK2 divider */
-
- regval = getreg32(STM32_RCC_CFGR);
- regval &= ~(RCC_CFGR_PPRE2_MASK | RCC_CFGR_HPRE_MASK);
- regval |= STM32_RCC_CFGR_PPRE2;
- regval |= RCC_CFGR_HPRE_SYSCLK;
- putreg32(regval, STM32_RCC_CFGR);
-
- /* Set the PCLK1 divider */
-
- regval = getreg32(STM32_RCC_CFGR);
- regval &= ~RCC_CFGR_PPRE1_MASK;
- regval |= STM32_RCC_CFGR_PPRE1;
- putreg32(regval, STM32_RCC_CFGR);
-
- regval = getreg32(STM32_RCC_CR);
- regval |= RCC_CR_PLL2ON;
- putreg32(regval, STM32_RCC_CR);
-
- /* Wait for PLL2 ready */
-
- while((getreg32(STM32_RCC_CR) & RCC_CR_PLL2RDY) == 0);
-
- /* Setup PLL3 for RMII clock on MCO */
-
- regval = getreg32(STM32_RCC_CFGR2);
- regval &= ~(RCC_CFGR2_PLL3MUL_MASK);
- regval |= RCC_CFGR2_PLL3MULx10;
- putreg32(regval, STM32_RCC_CFGR2);
-
- /* Switch PLL3 on */
-
- regval = getreg32(STM32_RCC_CR);
- regval |= RCC_CR_PLL3ON;
- putreg32(regval, STM32_RCC_CR);
-
- while ((getreg32(STM32_RCC_CR) & RCC_CR_PLL3RDY) == 0);
-
- /* Set main PLL source 8MHz * 9 => 72MHz*/
-
- regval = getreg32(STM32_RCC_CFGR);
- regval &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL_MASK);
- regval |= (RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL_CLKx9);
- putreg32(regval, STM32_RCC_CFGR);
-
- /* Switch main PLL on */
-
- regval = getreg32(STM32_RCC_CR);
- regval |= RCC_CR_PLLON;
- putreg32(regval, STM32_RCC_CR);
-
- while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLRDY) == 0);
-
- /* Select PLL as system clock source */
-
- regval = getreg32(STM32_RCC_CFGR);
- regval &= ~RCC_CFGR_SW_MASK;
- regval |= RCC_CFGR_SW_PLL;
- putreg32(regval, STM32_RCC_CFGR);
-
- /* Wait until PLL is used as the system clock source */
-
- while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_PLL) == 0);
-}
-#endif
diff --git a/nuttx/configs/shenzhou/include/board.h b/nuttx/configs/shenzhou/include/board.h
index 2e82742ec..8e4d89531 100644
--- a/nuttx/configs/shenzhou/include/board.h
+++ b/nuttx/configs/shenzhou/include/board.h
@@ -57,9 +57,18 @@
/* On-board crystal frequency is 25MHz (HSE) */
#define STM32_BOARD_XTAL 25000000ul
+
+/* PLL ouput is 72MHz */
+
+#define STM32_PLL_PREDIV2 RCC_CFGR2_PREDIV2d5 /* 25MHz / 5 => 5MHz */
+#define STM32_PLL_PLL2MUL RCC_CFGR2_PLL2MULx8 /* 5MHz * 8 => 40MHz */
+#define STM32_PLL_PREDIV1 RCC_CFGR2_PREDIV1d5 /* 40MHz / 5 => 8MHz */
+#define STM32_PLL_PLLMUL RCC_CFGR_PLLMUL_CLKx9 /* 8MHz * 9 => 72Mhz */
#define STM32_PLL_FREQUENCY (72000000)
-#define STM32_SYSCLK_FREQUENCY STM32_PLL_FREQUENCY
+/* SYCLLK and HCLK are the PLL frequency */
+
+#define STM32_SYSCLK_FREQUENCY STM32_PLL_FREQUENCY
#define STM32_HCLK_FREQUENCY STM32_PLL_FREQUENCY
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
@@ -88,6 +97,12 @@
#define STM32_APB1_TIM6_CLKIN (STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM7_CLKIN (STM32_PCLK1_FREQUENCY)
+/* MCO output */
+
+#if defined(CONFIG_STM32_MII_MCO) || defined(CONFIG_STM32_RMII_MCO)
+# define STM32_PLL_PLL3MUL RCC_CFGR2_PLL3MULx10
+#endif
+
/* LED definitions ******************************************************************/
/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
* way. The following definitions are used to access individual LEDs.
@@ -317,19 +332,6 @@
void stm32_boardinitialize(void);
/************************************************************************************
- * Name: stm32_board_clockconfig
- *
- * Description:
- * Any STM32 board may replace the "standard" board clock configuration logic with
- * its own, custom clock cofiguration logic.
- *
- ************************************************************************************/
-
-#ifdef CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG
-void stm32_board_clockconfig(void);
-#endif
-
-/************************************************************************************
* Button support.
*
* Description:
diff --git a/nuttx/configs/shenzhou/nsh/defconfig b/nuttx/configs/shenzhou/nsh/defconfig
index 70d9540db..f231b2632 100644
--- a/nuttx/configs/shenzhou/nsh/defconfig
+++ b/nuttx/configs/shenzhou/nsh/defconfig
@@ -161,7 +161,7 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y
# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
# CONFIG_STM32_JTAG_SW_ENABLE is not set
# CONFIG_STM32_FORCEPOWER is not set
-CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y
+# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set`
#
# SPI Configuration
diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile
index 50ddaa5ca..c12a251f0 100644
--- a/nuttx/configs/shenzhou/src/Makefile
+++ b/nuttx/configs/shenzhou/src/Makefile
@@ -42,10 +42,6 @@ AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = up_boot.c up_spi.c up_mmcsd.c
-ifeq ($(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG),y)
-CSRCS += up_clockconfig.c
-endif
-
ifeq ($(CONFIG_HAVE_CXX),y)
CSRCS += up_cxxinitialize.c
endif
diff --git a/nuttx/configs/shenzhou/src/up_clockconfig.c b/nuttx/configs/shenzhou/src/up_clockconfig.c
deleted file mode 100644
index 6c3bd56e1..000000000
--- a/nuttx/configs/shenzhou/src/up_clockconfig.c
+++ /dev/null
@@ -1,167 +0,0 @@
-/************************************************************************************
- * configs/olimex-stm32-p107/src/up_boot.c
- * arch/arm/src/board/up_boot.c
- *
- * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <debug.h>
-
-#include <arch/board/board.h>
-
-#include "up_arch.h"
-
-/************************************************************************************
- * Pre-processor Definitions
- ************************************************************************************/
-
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: stm32_board_clockconfig
- *
- * Description:
- * Any STM32 board may replace the "standard" board clock configuration logic with
- * its own, custom clock cofiguration logic.
- *
- ************************************************************************************/
-
-#ifdef CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG
-void stm32_board_clockconfig(void)
-{
- uint32_t regval;
-
- regval = getreg32(STM32_RCC_CR);
- regval &= ~RCC_CR_HSEBYP; /* Disable HSE clock bypass */
- regval |= RCC_CR_HSEON; /* Enable HSE */
- putreg32(regval, STM32_RCC_CR);
-
- /* Set flash wait states
- * Sysclk runs with 72MHz -> 2 waitstates.
- * 0WS from 0-24MHz
- * 1WS from 24-48MHz
- * 2WS from 48-72MHz
- */
-
- regval = getreg32(STM32_FLASH_ACR);
- regval &= ~FLASH_ACR_LATENCY_MASK;
- regval |= (FLASH_ACR_LATENCY_2|FLASH_ACR_PRTFBE);
- putreg32(regval, STM32_FLASH_ACR);
-
- regval = getreg32(STM32_RCC_CFGR2);
- regval &= ~(RCC_CFGR2_PREDIV2_MASK
- | RCC_CFGR2_PLL2MUL_MASK
- | RCC_CFGR2_PREDIV1SRC_MASK
- | RCC_CFGR2_PREDIV1_MASK);
- regval |= RCC_CFGR2_PREDIV2d5; /* 25MHz / 5 */
- regval |= RCC_CFGR2_PLL2MULx8; /* 5MHz * 8 => 40MHz */
- regval |= RCC_CFGR2_PREDIV1SRC_PLL2; /* Use PLL2 as input for PREDIV1 */
- regval |= RCC_CFGR2_PREDIV1d5; /* 40MHz / 5 => 8MHz */
- putreg32(regval, STM32_RCC_CFGR2);
-
- /* Set the PCLK2 divider */
-
- regval = getreg32(STM32_RCC_CFGR);
- regval &= ~(RCC_CFGR_PPRE2_MASK | RCC_CFGR_HPRE_MASK);
- regval |= STM32_RCC_CFGR_PPRE2;
- regval |= RCC_CFGR_HPRE_SYSCLK;
- putreg32(regval, STM32_RCC_CFGR);
-
- /* Set the PCLK1 divider */
-
- regval = getreg32(STM32_RCC_CFGR);
- regval &= ~RCC_CFGR_PPRE1_MASK;
- regval |= STM32_RCC_CFGR_PPRE1;
- putreg32(regval, STM32_RCC_CFGR);
-
- regval = getreg32(STM32_RCC_CR);
- regval |= RCC_CR_PLL2ON;
- putreg32(regval, STM32_RCC_CR);
-
- /* Wait for PLL2 ready */
-
- while((getreg32(STM32_RCC_CR) & RCC_CR_PLL2RDY) == 0);
-
- /* Setup PLL3 for RMII clock on MCO */
-
- regval = getreg32(STM32_RCC_CFGR2);
- regval &= ~(RCC_CFGR2_PLL3MUL_MASK);
- regval |= RCC_CFGR2_PLL3MULx10;
- putreg32(regval, STM32_RCC_CFGR2);
-
- /* Switch PLL3 on */
-
- regval = getreg32(STM32_RCC_CR);
- regval |= RCC_CR_PLL3ON;
- putreg32(regval, STM32_RCC_CR);
-
- while ((getreg32(STM32_RCC_CR) & RCC_CR_PLL3RDY) == 0);
-
- /* Set main PLL source 8MHz * 9 => 72MHz*/
-
- regval = getreg32(STM32_RCC_CFGR);
- regval &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL_MASK);
- regval |= (RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL_CLKx9);
- putreg32(regval, STM32_RCC_CFGR);
-
- /* Switch main PLL on */
-
- regval = getreg32(STM32_RCC_CR);
- regval |= RCC_CR_PLLON;
- putreg32(regval, STM32_RCC_CR);
-
- while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLRDY) == 0);
-
- /* Select PLL as system clock source */
-
- regval = getreg32(STM32_RCC_CFGR);
- regval &= ~RCC_CFGR_SW_MASK;
- regval |= RCC_CFGR_SW_PLL;
- putreg32(regval, STM32_RCC_CFGR);
-
- /* Wait until PLL is used as the system clock source */
-
- while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_PLL) == 0);
-}
-#endif