summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-03-29 15:34:48 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-03-29 15:34:48 -0600
commit79a68f1bd62fdea08b88bc0cd75fcb275bf108f7 (patch)
tree28981bc3ed4ff2fb9c7cd30232fb3d43bc8ff8fb /nuttx/arch
parent139948c34f21f92f0ab5b603abad8ac9de058c25 (diff)
downloadpx4-nuttx-79a68f1bd62fdea08b88bc0cd75fcb275bf108f7.tar.gz
px4-nuttx-79a68f1bd62fdea08b88bc0cd75fcb275bf108f7.tar.bz2
px4-nuttx-79a68f1bd62fdea08b88bc0cd75fcb275bf108f7.zip
The STM32F4Discovery board doesn't come with a Low speed external oscillator so the default LSE source for the RTC doesn't work.
In stm32_rtcc.c the up_rtcinitialize() logic doesn't work with the LSI. The check on RTC_MAGIC on the BK0R register lead to rtc_setup() call that rightfully enables the lsi clock; but the next times, when the rtc is already setup, the rtc_resume() call does NOT start the lsi clock! The right place to put LSE/LSI initialisation is inside stm32_stdclockconfig() in stm32fxxxxx_rcc.c. Doing this I checked the possible uses of the LSI and the LSE sources: the LSI can be used for RTC and/or the IWDG, while the LSE only for the RTC (and to output the MCO1 pin).. This change is not verifed for any other platforms. From Leo Aloe3132
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_lse.c62
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_lsi.c4
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_rtc.c12
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_rtc.h54
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_rtcc.c307
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_rtcounter.c8
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c50
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c36
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f30xxx_rcc.c60
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f37xxx_rcc.c58
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c54
-rw-r--r--nuttx/arch/arm/src/stm32/stm32l15xxx_rcc.c87
13 files changed, 501 insertions, 293 deletions
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index cff565ae4..d1b2fa41f 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -3418,13 +3418,11 @@ config RTC_LSECLOCK
config RTC_LSICLOCK
bool "LSI clock"
- depends on !STM32_STM32L15XX
---help---
Drive the RTC with the LSI clock
config RTC_HSECLOCK
bool "HSE clock"
- depends on !STM32_STM32L15XX
---help---
Drive the RTC with the HSE clock, divided down to 1MHz.
diff --git a/nuttx/arch/arm/src/stm32/stm32_lse.c b/nuttx/arch/arm/src/stm32/stm32_lse.c
index 56d68b1dc..3ee6f3a50 100644
--- a/nuttx/arch/arm/src/stm32/stm32_lse.c
+++ b/nuttx/arch/arm/src/stm32/stm32_lse.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_lse.c
*
- * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.orgr>
*
* Redistribution and use in source and binary forms, with or without
@@ -46,7 +46,7 @@
#include "stm32_waste.h"
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
/****************************************************************************
@@ -65,30 +65,24 @@
* Name: stm32_rcc_enablelse
*
* Description:
- * Enable the External Low-Speed (LSE) oscillator and, if the RTC is
- * configured, setup the LSE as the RTC clock source, and enable the RTC.
- *
- * For the STM32L15X family, this will also select the LSE as the clock
- * source of the LCD.
+ * Enable the External Low-Speed (LSE) oscillator.
*
* Todo:
* Check for LSE good timeout and return with -1,
*
****************************************************************************/
-#ifdef CONFIG_STM32_STM32L15XX
+
void stm32_rcc_enablelse(void)
{
- uint16_t pwrcr;
-
/* The LSE is in the RTC domain and write access is denied to this domain
* after reset, you have to enable write access using DBP bit in the PWR CR
* register before to configuring the LSE.
*/
- pwrcr = getreg16(STM32_PWR_CR);
- putreg16(pwrcr | PWR_CR_DBP, STM32_PWR_CR);
+ stm32_pwr_enablebkp(true);
+#if defined(CONFIG_STM32_STM32L15XX)
/* Enable the External Low-Speed (LSE) oscillator by setting the LSEON bit
* the RCC CSR register.
*/
@@ -102,34 +96,7 @@ void stm32_rcc_enablelse(void)
up_waste();
}
- /* The primariy purpose of the LSE clock is to drive the RTC with an accurate
- * clock source. In the STM32L family, the RTC and the LCD are coupled so
- * that must use the same clock source. Calling this function will select
- * the LSE will be used to drive the LCD as well.
- */
-
-#if defined(CONFIG_STM32_LCD) || defined(CONFIG_RTC)
- /* Select LSE as RTC/LCD Clock Source by setting the RTCSEL field of the RCC
- * CSR register.
- */
-
- modifyreg32(STM32_RCC_CSR, RCC_CSR_RTCSEL_MASK, RCC_CSR_RTCSEL_LSE);
-
-#if defined(CONFIG_RTC)
- /* Enable the RTC Clock by setting the RTCEN bit in the RCC CSR register */
-
- modifyreg32(STM32_RCC_CSR, 0, RCC_CSR_RTCEN);
-#endif
-#endif
-
- /* Restore the previous state of the DBP bit */
-
- putreg16(pwrcr, STM32_PWR_CR);
-}
#else
-
-void stm32_rcc_enablelse(void)
-{
/* Enable the External Low-Speed (LSE) oscillator by setting the LSEON bit
* the RCC BDCR register.
*/
@@ -143,21 +110,8 @@ void stm32_rcc_enablelse(void)
up_waste();
}
- /* The primariy purpose of the LSE clock is to drive the RTC. The RTC could
- * also be driven by the LSI (but that would be very inaccurate) or by the
- * HSE (but that would prohibit low-power operation)
- */
-
-#ifdef CONFIG_RTC
- /* Select LSE as RTC Clock Source by setting the RTCSEL field of the RCC
- * BDCR register.
- */
-
- modifyreg16(STM32_RCC_BDCR, RCC_BDCR_RTCSEL_MASK, RCC_BDCR_RTCSEL_LSE);
+#endif
- /* Enable the RTC Clock by setting the RTCEN bit in the RCC BDCR register */
+ stm32_pwr_enablebkp(false);
- modifyreg16(STM32_RCC_BDCR, 0, RCC_BDCR_RTCEN);
-#endif
}
-#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32_lsi.c b/nuttx/arch/arm/src/stm32/stm32_lsi.c
index e365fbf06..1518cd149 100644
--- a/nuttx/arch/arm/src/stm32/stm32_lsi.c
+++ b/nuttx/arch/arm/src/stm32/stm32_lsi.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_lsi.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.orgr>
*
* Redistribution and use in source and binary forms, with or without
@@ -44,7 +44,7 @@
#include "stm32_rcc.h"
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
/****************************************************************************
diff --git a/nuttx/arch/arm/src/stm32/stm32_rtc.c b/nuttx/arch/arm/src/stm32/stm32_rtc.c
index 9dc5b2097..a65a1362a 100644
--- a/nuttx/arch/arm/src/stm32/stm32_rtc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_rtc.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_rtc.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -40,7 +40,6 @@
#include <nuttx/config.h>
#include "chip.h"
-#include "stm32_rtc.h"
/****************************************************************************
* Pre-processor Definitions
@@ -68,8 +67,8 @@
* chip.h that can associate an STM32 part number with an STM32 family.
*/
-/* The STM32 F1 has a simple battery-backed counter for its RTC and has a separate
- * block for the BKP registers.
+/* The STM32 F1 has a simple battery-backed counter for its RTC and has a
+ * separate block for the BKP registers.
*/
#if defined(CONFIG_STM32_STM32F10XX)
@@ -80,8 +79,7 @@
* the RTCC in these families.
*/
-#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F30XX) ||\
- defined(CONFIG_STM32_STM32F40XX)
+#elif defined(CONFIG_STM32_STM32L15XX) || defined(CONFIG_STM32_STM32F20XX) || \
+ defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F40XX)
# include "stm32_rtcc.c"
#endif
-
diff --git a/nuttx/arch/arm/src/stm32/stm32_rtc.h b/nuttx/arch/arm/src/stm32/stm32_rtc.h
index 9cd0cc131..19ea7621b 100644
--- a/nuttx/arch/arm/src/stm32/stm32_rtc.h
+++ b/nuttx/arch/arm/src/stm32/stm32_rtc.h
@@ -1,4 +1,4 @@
-/************************************************************************************
+/****************************************************************************
* arch/arm/src/stm32/stm32_rtc.h
*
* Copyright (C) 2011 Uros Platise. All rights reserved.
@@ -33,11 +33,11 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************************************/
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Included Files
- ************************************************************************************/
+ ****************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32_STM32_RTC_H
#define __ARCH_ARM_SRC_STM32_STM32_RTC_H
@@ -59,17 +59,17 @@
* the RTCC in these families.
*/
-#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F30XX) ||\
- defined(CONFIG_STM32_STM32F40XX)
+#elif defined(CONFIG_STM32_STM32L15XX) || defined(CONFIG_STM32_STM32F20XX) || \
+ defined(CONFIG_STM32_STM32F30XX) || defined(CONFIG_STM32_STM32F40XX)
# include "chip/stm32_rtcc.h"
#endif
-/************************************************************************************
+/****************************************************************************
* Pre-processor Definitions
- ************************************************************************************/
+ ****************************************************************************/
-#define STM32_RTC_PRESCALER_SECOND 32767 /* Default prescaler to get a second base */
-#define STM32_RTC_PRESCALER_MIN 1 /* Maximum speed of 16384 Hz */
+#define STM32_RTC_PRESCALER_SECOND 32767 /* Default prescaler to get a second base */
+#define STM32_RTC_PRESCALER_MIN 1 /* Maximum speed of 16384 Hz */
/****************************************************************************
* Public Types
@@ -94,22 +94,22 @@ extern "C"
#define EXTERN extern
#endif
-/************************************************************************************
+/****************************************************************************
* Public Functions
- ************************************************************************************/
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Name: stm32_rtc_getdatetime_with_subseconds
*
* Description:
* Get the current date and time from the date/time RTC. This interface
* is only supported by the date/time RTC hardware implementation.
- * It is used to replace the system timer. It is only used by the RTOS during
- * initialization to set up the system time when CONFIG_RTC and CONFIG_RTC_DATETIME
- * are selected (and CONFIG_RTC_HIRES is not).
+ * It is used to replace the system timer. It is only used by the RTOS
+ * during initialization to set up the system time when CONFIG_RTC and
+ * CONFIG_RTC_DATETIME are selected (and CONFIG_RTC_HIRES is not).
*
- * NOTE: Some date/time RTC hardware is capability of sub-second accuracy. That
- * sub-second accuracy is returned through 'nsec'.
+ * NOTE: Some date/time RTC hardware is capability of sub-second accuracy.
+ * Thatsub-second accuracy is returned through 'nsec'.
*
* Input Parameters:
* tp - The location to return the high resolution time value.
@@ -118,19 +118,19 @@ extern "C"
* Returned Value:
* Zero (OK) on success; a negated errno on failure
*
- ************************************************************************************/
+ ****************************************************************************/
#ifdef CONFIG_STM32_HAVE_RTC_SUBSECONDS
int stm32_rtc_getdatetime_with_subseconds(FAR struct tm *tp, FAR long *nsec);
#endif
-/************************************************************************************
+/****************************************************************************
* Name: stm32_rtc_setdatetime
*
* Description:
* Set the RTC to the provided time. RTC implementations which provide
- * up_rtc_getdatetime() (CONFIG_RTC_DATETIME is selected) should provide this
- * function.
+ * up_rtc_getdatetime() (CONFIG_RTC_DATETIME is selected) should provide
+ * this function.
*
* Input Parameters:
* tp - the time to use
@@ -138,14 +138,14 @@ int stm32_rtc_getdatetime_with_subseconds(FAR struct tm *tp, FAR long *nsec);
* Returned Value:
* Zero (OK) on success; a negated errno on failure
*
- ************************************************************************************/
+ ****************************************************************************/
#ifdef CONFIG_RTC_DATETIME
struct tm;
int stm32_rtc_setdatetime(FAR const struct tm *tp);
#endif
-/************************************************************************************
+/****************************************************************************
* Name: stm32_rtc_setalarm
*
* Description:
@@ -158,14 +158,14 @@ int stm32_rtc_setdatetime(FAR const struct tm *tp);
* Returned Value:
* Zero (OK) on success; a negated errno on failure
*
- ************************************************************************************/
+ ****************************************************************************/
#ifdef CONFIG_RTC_ALARM
struct timespec;
int stm32_rtc_setalarm(FAR const struct timespec *tp, alarmcb_t callback);
#endif
-/************************************************************************************
+/****************************************************************************
* Name: stm32_rtc_cancelalarm
*
* Description:
@@ -177,7 +177,7 @@ int stm32_rtc_setalarm(FAR const struct timespec *tp, alarmcb_t callback);
* Returned Value:
* Zero (OK) on success; a negated errno on failure
*
- ************************************************************************************/
+ ****************************************************************************/
#ifdef CONFIG_RTC_ALARM
int stm32_rtc_cancelalarm(void);
diff --git a/nuttx/arch/arm/src/stm32/stm32_rtcc.c b/nuttx/arch/arm/src/stm32/stm32_rtcc.c
index 884ac8cac..a520b3b74 100644
--- a/nuttx/arch/arm/src/stm32/stm32_rtcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_rtcc.c
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_rtcc.c
*
- * Copyright (C) 2012-2014 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -93,6 +93,26 @@
#define INITMODE_TIMEOUT (0x00010000)
#define RTC_MAGIC (0xfacefeee)
+/* Proxy definitions to make the same code work for all the STM32 series ************/
+
+#if defined(CONFIG_STM32_STM32L15XX)
+# define STM32_RCC_XXX STM32_RCC_CSR
+# define RCC_XXX_YYYRST RCC_CSR_RTCRST
+# define RCC_XXX_RTCEN RCC_CSR_RTCEN
+# define RCC_XXX_RTCSEL_MASK RCC_CSR_RTCSEL_MASK
+# define RCC_XXX_RTCSEL_LSE RCC_CSR_RTCSEL_LSE
+# define RCC_XXX_RTCSEL_LSI RCC_CSR_RTCSEL_LSI
+# define RCC_XXX_RTCSEL_HSE RCC_CSR_RTCSEL_HSE
+#else
+# define STM32_RCC_XXX STM32_RCC_BDCR
+# define RCC_XXX_YYYRST RCC_BDCR_BDRST
+# define RCC_XXX_RTCEN RCC_BDCR_RTCEN
+# define RCC_XXX_RTCSEL_MASK RCC_BDCR_RTCSEL_MASK
+# define RCC_XXX_RTCSEL_LSE RCC_BDCR_RTCSEL_LSE
+# define RCC_XXX_RTCSEL_LSI RCC_BDCR_RTCSEL_LSI
+# define RCC_XXX_RTCSEL_HSE RCC_BDCR_RTCSEL_HSE
+#endif
+
/* Debug ****************************************************************************/
#ifdef CONFIG_DEBUG_RTC
@@ -232,7 +252,7 @@ static void rtc_wprunlock(void)
* 1. Write 0xCA into the RTC_WPR register.
* 2. Write 0x53 into the RTC_WPR register.
*
- * Writing a wrong key reactivates the write protection.
+ * Writing a wrong key re-activates the write protection.
*/
putreg32(0xca, STM32_RTC_WPR);
@@ -255,12 +275,12 @@ static void rtc_wprunlock(void)
static inline void rtc_wprlock(void)
{
- /* Writing any wrong key reactivates the write protection. */
+ /* Writing any wrong key re-activates the write protection. */
putreg32(0xff, STM32_RTC_WPR);
- /* Disable write access to the backup domain (RTC registers, RTC backup data registers
- * and backup SRAM).
+ /* Disable write access to the backup domain (RTC registers, RTC backup data
+ * registers and backup SRAM).
*/
stm32_pwr_enablebkp(false);
@@ -293,7 +313,7 @@ static int rtc_synchwait(void)
/* Clear Registers synchronization flag (RSF) */
- regval = getreg32(STM32_RTC_ISR);
+ regval = getreg32(STM32_RTC_ISR);
regval &= ~RTC_ISR_RSF;
putreg32(regval, STM32_RTC_ISR);
@@ -457,105 +477,49 @@ static int rtc_setup(void)
uint32_t regval;
int ret;
-#ifndef CONFIG_STM32_STM32L15XX
- /* We might be changing RTCSEL - to ensure such changes work, we must reset the
- * backup domain
- */
-
- modifyreg32(STM32_RCC_BDCR, 0, RCC_BDCR_BDRST);
- modifyreg32(STM32_RCC_BDCR, RCC_BDCR_BDRST, 0);
-
- /* Some boards do not have the external 32khz oscillator installed, for those
- * boards we must fallback to the crummy internal RC clock or the external high
- * rate clock
- */
-
-#ifdef CONFIG_RTC_HSECLOCK
- /* Use the HSE clock as the input to the RTC block */
-
- modifyreg32(STM32_RCC_BDCR, RCC_BDCR_RTCSEL_MASK, RCC_BDCR_RTCSEL_HSE);
-
- /* Enable the RTC Clock by setting the RTCEN bit in the RCC BDCR register */
-
- modifyreg32(STM32_RCC_BDCR, 0, RCC_BDCR_RTCEN);
-
-#elif defined(CONFIG_RTC_LSICLOCK)
- /* Enable the LSI clock */
-
- stm32_rcc_enablelsi();
-
- /* Use the LSI clock as the input to the RTC block */
-
- modifyreg32(STM32_RCC_BDCR, RCC_BDCR_RTCSEL_MASK, RCC_BDCR_RTCSEL_LSI);
-
- /* Enable the RTC Clock by setting the RTCEN bit in the RCC BDCR register */
-
- modifyreg32(STM32_RCC_BDCR, 0, RCC_BDCR_RTCEN);
-
-#else
- /* Enable the LSE clock */
-
- stm32_rcc_enablelse();
-
-#endif
-#else
- /* Enable the LSE clock */
-
- stm32_rcc_enablelse();
+ /* Disable the write protection for RTC registers */
-#endif /* CONFIG_STM32_STM32L15XX */
+ rtc_wprunlock();
- /* Wait for the RTC Time and Date registers to be synchronized with RTC APB
- * clock.
- */
+ /* Set Initialization mode */
- ret = rtc_synchwait();
+ ret = rtc_enterinit();
if (ret == OK)
{
- /* Disable the write protection for RTC registers */
-
- rtc_wprunlock();
-
- /* Set Initialization mode */
-
- ret = rtc_enterinit();
- if (ret == OK)
- {
- /* Set the 24 hour format by clearing the FMT bit in the RTC
- * control register
- */
+ /* Set the 24 hour format by clearing the FMT bit in the RTC
+ * control register
+ */
- regval = getreg32(STM32_RTC_CR);
- regval &= ~RTC_CR_FMT;
- putreg32(regval, STM32_RTC_CR);
+ regval = getreg32(STM32_RTC_CR);
+ regval &= ~RTC_CR_FMT;
+ putreg32(regval, STM32_RTC_CR);
- /* Configure RTC pre-scaler with the required values */
+ /* Configure RTC pre-scaler with the required values */
#ifdef CONFIG_RTC_HSECLOCK
- /* For a 1 MHz clock this yields 0.9999360041 Hz on the second
- * timer - which is pretty close.
- */
+ /* For a 1 MHz clock this yields 0.9999360041 Hz on the second
+ * timer - which is pretty close.
+ */
- putreg32(((uint32_t)7182 << RTC_PRER_PREDIV_S_SHIFT) |
- ((uint32_t)0x7f << RTC_PRER_PREDIV_A_SHIFT),
- STM32_RTC_PRER);
+ putreg32(((uint32_t)7182 << RTC_PRER_PREDIV_S_SHIFT) |
+ ((uint32_t)0x7f << RTC_PRER_PREDIV_A_SHIFT),
+ STM32_RTC_PRER);
#else
- /* Correct values for 1 32.768 KHz LSE clock */
+ /* Correct values for 32.768 KHz LSE clock and inaccurate LSI clock */
- putreg32(((uint32_t)0xff << RTC_PRER_PREDIV_S_SHIFT) |
- ((uint32_t)0x7f << RTC_PRER_PREDIV_A_SHIFT),
- STM32_RTC_PRER);
+ putreg32(((uint32_t)0xff << RTC_PRER_PREDIV_S_SHIFT) |
+ ((uint32_t)0x7f << RTC_PRER_PREDIV_A_SHIFT),
+ STM32_RTC_PRER);
#endif
- /* Exit RTC initialization mode */
+ /* Exit RTC initialization mode */
- rtc_exitinit();
- }
+ rtc_exitinit();
+ }
- /* Re-enable the write protection for RTC registers */
+ /* Re-enable the write protection for RTC registers */
- rtc_wprlock();
- }
+ rtc_wprlock();
return ret;
}
@@ -575,20 +539,11 @@ static int rtc_setup(void)
*
************************************************************************************/
-static int rtc_resume(void)
+static void rtc_resume(void)
{
#ifdef CONFIG_RTC_ALARM
uint32_t regval;
-#endif
- int ret;
-
- /* Wait for the RTC Time and Date registers to be synchronized with RTC APB
- * clock.
- */
-
- ret = rtc_synchwait();
-#ifdef CONFIG_RTC_ALARM
/* Clear the RTC alarm flags */
regval = getreg32(STM32_RTC_ISR);
@@ -599,8 +554,6 @@ static int rtc_resume(void)
putreg32((1 << 17), STM32_EXTI_PR);
#endif
-
- return ret;
}
/************************************************************************************
@@ -647,7 +600,7 @@ static int rtc_interrupt(int irq, void *context)
int up_rtcinitialize(void)
{
- uint32_t regval;
+ uint32_t regval, clksrc, tr_bkp, dr_bkp;
int ret;
int maxretry = 10;
int nretry = 0;
@@ -660,70 +613,156 @@ int up_rtcinitialize(void)
rtc_dumpregs("On reset");
- /* Enable the External Low-Speed (LSE) Oscillator setup the LSE as the RTC clock
- * source, and enable the RTC.
- */
+ /* Select the clock source */
+ /* Save the token before losing it when resetting */
- /* Loop, attempting to initialize/resume the RTC. This loop is necessary
- * because it seems that occasionally it takes longer to initialize the RTC
- * (the actual failure is in rtc_synchwait()).
- */
+ regval = getreg32(STM32_RTC_BK0R);
- do
+ stm32_pwr_enablebkp(true);
+
+ if (regval != RTC_MAGIC)
{
- /* Check if the one-time initialization of the RTC has already been
- * performed. We can determine this by checking if the magic number
- * has been writing to to back-up date register DR0.
+ /* We might be changing RTCSEL - to ensure such changes work, we must reset the
+ * backup domain (having backed up the RTC_MAGIC token)
*/
- regval = getreg32(STM32_RTC_BK0R);
- if (regval != RTC_MAGIC)
- {
- rtclldbg("Do setup\n");
+ modifyreg32(STM32_RCC_XXX, 0, RCC_XXX_YYYRST);
+ modifyreg32(STM32_RCC_XXX, RCC_XXX_YYYRST, 0);
- /* Perform the one-time setup of the LSE clocking to the RTC */
+ /* Some boards do not have the external 32khz oscillator installed, for those
+ * boards we must fallback to the crummy internal RC clock or the external high
+ * rate clock
+ */
- ret = rtc_setup();
+#ifdef CONFIG_RTC_HSECLOCK
+ /* Use the HSE clock as the input to the RTC block */
- /* Enable write access to the backup domain (RTC registers, RTC
- * backup data registers and backup SRAM).
- */
+ modifyreg32(STM32_RCC_XXX, RCC_XXX_RTCSEL_MASK, RCC_XXX_RTCSEL_HSE);
- stm32_pwr_enablebkp(true);
+#elif defined(CONFIG_RTC_LSICLOCK)
+ /* Use the LSI clock as the input to the RTC block */
- /* Remember that the RTC is initialized */
+ modifyreg32(STM32_RCC_XXX, RCC_XXX_RTCSEL_MASK, RCC_XXX_RTCSEL_LSI);
- putreg32(RTC_MAGIC, STM32_RTC_BK0R);
- }
- else
+#elif defined(CONFIG_RTC_LSECLOCK)
+ /* Use the LSE clock as the input to the RTC block */
+
+ modifyreg32(STM32_RCC_XXX, RCC_XXX_RTCSEL_MASK, RCC_XXX_RTCSEL_LSE);
+
+#endif
+ /* Enable the RTC Clock by setting the RTCEN bit in the RCC register */
+
+ modifyreg32(STM32_RCC_XXX, 0, RCC_XXX_RTCEN);
+ }
+ else /* The RTC is already in use: check if the clock source is changed */
+ {
+ clksrc = getreg32(STM32_RCC_XXX);
+
+#if defined(CONFIG_RTC_HSECLOCK)
+ if ((clksrc & RCC_XXX_RTCSEL_MASK) != RCC_XXX_RTCSEL_HSE)
+#elif defined(CONFIG_RTC_LSICLOCK)
+ if ((clksrc & RCC_XXX_RTCSEL_MASK) != RCC_XXX_RTCSEL_LSI)
+#elif defined(CONFIG_RTC_LSECLOCK)
+ if ((clksrc & RCC_XXX_RTCSEL_MASK) != RCC_XXX_RTCSEL_LSE)
+#endif
{
- rtclldbg("Do resume\n");
+ tr_bkp = getreg32(STM32_RTC_TR);
+ dr_bkp = getreg32(STM32_RTC_DR);
+ modifyreg32(STM32_RCC_XXX, 0, RCC_XXX_YYYRST);
+ modifyreg32(STM32_RCC_XXX, RCC_XXX_YYYRST, 0);
+
+#if defined(CONFIG_RTC_HSECLOCK)
+ /* Change to the new clock as the input to the RTC block */
+
+ modifyreg32(STM32_RCC_XXX, RCC_XXX_RTCSEL_MASK, RCC_XXX_RTCSEL_HSE);
+
+#elif defined(CONFIG_RTC_LSICLOCK)
+ modifyreg32(STM32_RCC_XXX, RCC_XXX_RTCSEL_MASK, RCC_XXX_RTCSEL_LSI);
+
+#elif defined(CONFIG_RTC_LSECLOCK)
+ modifyreg32(STM32_RCC_XXX, RCC_XXX_RTCSEL_MASK, RCC_XXX_RTCSEL_LSE);
+#endif
+
+ putreg32(tr_bkp,STM32_RTC_TR);
+ putreg32(dr_bkp,STM32_RTC_DR);
- /* RTC already set-up, just resume normal operation */
+ /* Remember that the RTC is initialized */
- ret = rtc_resume();
- rtc_dumpregs("Did resume");
+ putreg32(RTC_MAGIC, STM32_RTC_BK0R);
+
+ /* Enable the RTC Clock by setting the RTCEN bit in the RCC register */
+
+ modifyreg32(STM32_RCC_XXX, 0, RCC_XXX_RTCEN);
}
+ }
- /* Check that setup or resume returned successfully */
+ stm32_pwr_enablebkp(false);
+
+ /* Loop, attempting to initialize/resume the RTC. This loop is necessary
+ * because it seems that occasionally it takes longer to initialize the RTC
+ * (the actual failure is in rtc_synchwait()).
+ */
+
+ do
+ {
+ /* Wait for the RTC Time and Date registers to be synchronized with RTC APB
+ * clock.
+ */
+
+ ret = rtc_synchwait();
+
+ /* Check that rtc_syncwait() returned successfully */
switch (ret)
{
case OK:
{
- rtclldbg("setup/resume okay\n");
+ rtclldbg("rtc_syncwait() okay\n");
break;
}
default:
{
- rtclldbg("setup/resume failed (%d)\n", ret);
+ rtclldbg("rtc_syncwait() failed (%d)\n", ret);
break;
}
}
}
while (ret != OK && ++nretry < maxretry);
+ /* Check if the one-time initialization of the RTC has already been
+ * performed. We can determine this by checking if the magic number
+ * has been writing to to back-up date register DR0.
+ */
+
+ if (regval != RTC_MAGIC)
+ {
+ rtclldbg("Do setup\n");
+
+ /* Perform the one-time setup of the LSE clocking to the RTC */
+
+ ret = rtc_setup();
+
+ /* Enable write access to the backup domain (RTC registers, RTC
+ * backup data registers and backup SRAM).
+ */
+
+ stm32_pwr_enablebkp(true);
+
+ /* Remember that the RTC is initialized */
+
+ putreg32(RTC_MAGIC, STM32_RTC_BK0R);
+ }
+ else
+ {
+ rtclldbg("Do resume\n");
+
+ /* RTC already set-up, just resume normal operation */
+
+ rtc_resume();
+ rtc_dumpregs("Did resume");
+ }
+
/* Disable write access to the backup domain (RTC registers, RTC backup
* data registers and backup SRAM).
*/
@@ -733,7 +772,7 @@ int up_rtcinitialize(void)
if (ret != OK && nretry > 0)
{
rtclldbg("setup/resume ran %d times and failed with %d\n",
- nretry, ret);
+ nretry, ret);
return -ETIMEDOUT;
}
diff --git a/nuttx/arch/arm/src/stm32/stm32_rtcounter.c b/nuttx/arch/arm/src/stm32/stm32_rtcounter.c
index 7f030cbc3..e27f5a54d 100644
--- a/nuttx/arch/arm/src/stm32/stm32_rtcounter.c
+++ b/nuttx/arch/arm/src/stm32/stm32_rtcounter.c
@@ -117,6 +117,14 @@
# error "CONFIG_STM32_PWR is required for CONFIG_RTC"
#endif
+#ifdef CONFIG_STM32_STM32F10XX
+# if defined(CONFIG_RTC_HSECLOCK)
+# error "RTC with HSE clock not yet implemented for STM32F10XXX"
+# elif defined(CONFIG_RTC_LSICLOCK)
+# error "RTC with LSI clock not yet implemented for STM32F10XXX"
+# endif
+#endif
+
/* RTC/BKP Definitions *************************************************************/
/* STM32_RTC_PRESCALAR_VALUE
* RTC pre-scalar value. The RTC is driven by a 32,768Hz input clock. This input
diff --git a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c
index f46f0d104..3d8a45822 100644
--- a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32f10xxx_rcc.c
*
- * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011-2012, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -38,7 +38,7 @@
****************************************************************************/
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
/* Allow up to 100 milliseconds for the high speed clock to become ready.
@@ -80,7 +80,8 @@ static inline void rcc_reset(void)
putreg32(regval, STM32_RCC_CR);
regval = getreg32(STM32_RCC_CFGR); /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
- regval &= ~(RCC_CFGR_SW_MASK|RCC_CFGR_HPRE_MASK|RCC_CFGR_PPRE1_MASK|RCC_CFGR_PPRE2_MASK|RCC_CFGR_ADCPRE_MASK|RCC_CFGR_MCO_MASK);
+ regval &= ~(RCC_CFGR_SW_MASK|RCC_CFGR_HPRE_MASK|RCC_CFGR_PPRE1_MASK|
+ RCC_CFGR_PPRE2_MASK|RCC_CFGR_ADCPRE_MASK|RCC_CFGR_MCO_MASK);
putreg32(regval, STM32_RCC_CFGR);
regval = getreg32(STM32_RCC_CR); /* Reset HSEON, CSSON and PLLON bits */
@@ -188,13 +189,13 @@ static inline void rcc_enableahb(void)
static inline void rcc_enableapb1(void)
{
uint32_t regval;
+
#ifdef CONFIG_STM32_USB
/* USB clock divider for USB FS device. This bit must be valid before
* enabling the USB clock in the RCC_APB1ENR register. This bit can't be
* reset if the USB clock is enabled.
*/
-
regval = getreg32(STM32_RCC_CFGR);
regval &= ~RCC_CFGR_USBPRE;
regval |= STM32_CFGR_USBPRE;
@@ -208,6 +209,7 @@ static inline void rcc_enableapb1(void)
regval = getreg32(STM32_RCC_APB1ENR);
#ifdef CONFIG_STM32_TIM2
/* Timer 2 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM2EN;
#endif
@@ -215,6 +217,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM3
/* Timer 3 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM3EN;
#endif
@@ -222,6 +225,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM4
/* Timer 4 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM4EN;
#endif
@@ -229,6 +233,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM5
/* Timer 5 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM5EN;
#endif
@@ -236,6 +241,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM6
/* Timer 6 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM6EN;
#endif
@@ -243,6 +249,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM7
/* Timer 7 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM7EN;
#endif
@@ -250,6 +257,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM12
/* Timer 12 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM12EN;
#endif
@@ -257,6 +265,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM13
/* Timer 13 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM13EN;
#endif
@@ -264,6 +273,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM14
/* Timer 14 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM14EN;
#endif
@@ -313,6 +323,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_I2C1
/* I2C 1 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_I2C1EN;
#endif
@@ -320,6 +331,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_I2C2
/* I2C 2 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_I2C2EN;
#endif
@@ -427,6 +439,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM1
/* TIM1 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM1EN;
#endif
@@ -440,6 +453,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM8
/* TIM8 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM8EN;
#endif
@@ -452,13 +466,14 @@ static inline void rcc_enableapb2(void)
#endif
#ifdef CONFIG_STM32_ADC3
- /*ADC3 interface clock enable */
+ /* ADC3 interface clock enable */
regval |= RCC_APB2ENR_ADC3EN;
#endif
#ifdef CONFIG_STM32_TIM15
/* TIM15 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM15EN;
#endif
@@ -466,6 +481,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM16
/* TIM16 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM16EN;
#endif
@@ -473,6 +489,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM17
/* TIM17 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM17EN;
#endif
@@ -492,7 +509,8 @@ static inline void rcc_enableapb2(void)
* power clocking modes!
****************************************************************************/
-#if !defined(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG) && defined(CONFIG_STM32_CONNECTIVITYLINE)
+#if !defined(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG) && \
+ defined(CONFIG_STM32_CONNECTIVITYLINE)
static void stm32_stdclockconfig(void)
{
uint32_t regval;
@@ -550,9 +568,9 @@ static void stm32_stdclockconfig(void)
while ((getreg32(STM32_RCC_CR) & RCC_CR_PLL2RDY) == 0);
+#if defined(CONFIG_STM32_MII_MCO) || defined(CONFIG_STM32_RMII_MCO)
/* 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;
@@ -606,7 +624,8 @@ static void stm32_stdclockconfig(void)
* power clocking modes!
****************************************************************************/
-#if !defined(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG) && !defined(CONFIG_STM32_CONNECTIVITYLINE)
+#if !defined(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG) && \
+ !defined(CONFIG_STM32_CONNECTIVITYLINE)
static void stm32_stdclockconfig(void)
{
uint32_t regval;
@@ -614,7 +633,6 @@ static void stm32_stdclockconfig(void)
/* If the PLL is using the HSE, or the HSE is the system clock */
#if (STM32_CFGR_PLLSRC == RCC_CFGR_PLLSRC) || (STM32_SYSCLK_SW == RCC_CFGR_SW_HSE)
-
{
volatile int32_t timeout;
@@ -703,7 +721,7 @@ static void stm32_stdclockconfig(void)
#if STM32_SYSCLK_SW == RCC_CFGR_SW_PLL
- /* Set the PLL divider and multipler */
+ /* Set the PLL divider and multiplier */
regval = getreg32(STM32_RCC_CFGR);
regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK);
@@ -732,6 +750,18 @@ static void stm32_stdclockconfig(void)
/* Wait until the selected source is used as the system clock source */
while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) != STM32_SYSCLK_SWS);
+
+#if defined(CONFIG_STM32_IWDG) || defined(CONFIG_RTC_LSICLOCK)
+ /* Low speed internal clock source LSI */
+
+ stm32_rcc_enablelsi();
+#endif
+
+#if defined(CONFIG_RTC_LSECLOCK)
+ /* Low speed external clock source LSE */
+
+ stm32_rcc_enablelse();
+#endif
}
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c
index da65dd7d6..6ad500070 100644
--- a/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32f20xxx_rcc.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -44,7 +44,7 @@
*/
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
/* Allow up to 100 milliseconds for the high speed clock to become ready.
@@ -562,16 +562,16 @@ static void stm32_stdclockconfig(void)
/* Wait until the HSE is ready (or until a timeout elapsed) */
for (timeout = HSERDY_TIMEOUT; timeout > 0; timeout--)
- {
- /* Check if the HSERDY flag is the set in the CR */
+ {
+ /* Check if the HSERDY flag is the set in the CR */
- if ((getreg32(STM32_RCC_CR) & RCC_CR_HSERDY) != 0)
- {
- /* If so, then break-out with timeout > 0 */
+ if ((getreg32(STM32_RCC_CR) & RCC_CR_HSERDY) != 0)
+ {
+ /* If so, then break-out with timeout > 0 */
- break;
- }
- }
+ break;
+ }
+ }
/* Check for a timeout. If this timeout occurs, then we are hosed. We
* have no real back-up plan, although the following logic makes it look
@@ -657,6 +657,22 @@ static void stm32_stdclockconfig(void)
/* Wait until the PLL source is used as the system clock source */
while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) != RCC_CFGR_SWS_PLL);
+
+#if defined(CONFIG_STM32_IWDG) || defined(CONFIG_RTC_LSICLOCK)
+ /* Low speed internal clock source LSI */
+
+ stm32_rcc_enablelsi();
+#endif
+
+#if defined(CONFIG_RTC_LSECLOCK)
+ /* Low speed external clock source LSE
+ *
+ * TODO: There is another case where the LSE needs to
+ * be enabled: if the MCO1 pin selects LSE as source.
+ */
+
+ stm32_rcc_enablelse();
+#endif
}
}
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32f30xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f30xxx_rcc.c
index 1209013d8..fcc191bc4 100644
--- a/nuttx/arch/arm/src/stm32/stm32f30xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f30xxx_rcc.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32f30xxx_rcc.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -38,7 +38,7 @@
****************************************************************************/
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
/* Allow up to 100 milliseconds for the high speed clock to become ready.
@@ -200,6 +200,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM2
/* Timer 2 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM2EN;
#endif
@@ -207,6 +208,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM3
/* Timer 3 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM3EN;
#endif
@@ -214,6 +216,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM4
/* Timer 4 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM4EN;
#endif
@@ -221,6 +224,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM6
/* Timer 6 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM6EN;
#endif
@@ -228,6 +232,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM7
/* Timer 7 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM7EN;
#endif
@@ -277,6 +282,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_I2C1
/* I2C 1 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_I2C1EN;
#endif
@@ -284,6 +290,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_I2C2
/* I2C 2 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_I2C2EN;
#endif
@@ -342,6 +349,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM1
/* TIM1 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM1EN;
#endif
@@ -355,6 +363,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM8
/* TIM8 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM8EN;
#endif
@@ -368,6 +377,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM15
/* TIM15 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM15EN;
#endif
@@ -375,6 +385,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM16
/* TIM16 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM16EN;
#endif
@@ -382,6 +393,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM17
/* TIM17 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM17EN;
#endif
@@ -515,7 +527,8 @@ static void stm32_stdclockconfig(void)
* power clocking modes!
****************************************************************************/
-#if !defined(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG) && !defined(CONFIG_STM32_CONNECTIVITYLINE)
+#if !defined(CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG) && \
+ !defined(CONFIG_STM32_CONNECTIVITYLINE)
static void stm32_stdclockconfig(void)
{
uint32_t regval;
@@ -523,7 +536,6 @@ static void stm32_stdclockconfig(void)
/* If the PLL is using the HSE, or the HSE is the system clock */
#if (STM32_CFGR_PLLSRC == RCC_CFGR_PLLSRC) || (STM32_SYSCLK_SW == RCC_CFGR_SW_HSE)
-
{
volatile int32_t timeout;
@@ -551,16 +563,16 @@ static void stm32_stdclockconfig(void)
if (timeout == 0)
{
/* In the case of a timeout starting the HSE, we really don't have a
- * strategy. This is almost always a hardware failure or misconfiguration.
+ * strategy. This is almost always a hardware failure or
+ * misconfiguration.
*/
return;
}
}
- /* If this is a value-line part and we are using the HSE as the PLL */
-
# if defined(CONFIG_STM32_VALUELINE) && (STM32_CFGR_PLLSRC == RCC_CFGR_PLLSRC)
+ /* If this is a value-line part and we are using the HSE as the PLL */
# if (STM32_CFGR_PLLXTPRE >> 17) != (STM32_CFGR2_PREDIV1 & 1)
# error STM32_CFGR_PLLXTPRE must match the LSB of STM32_CFGR2_PREDIV1
@@ -574,17 +586,14 @@ static void stm32_stdclockconfig(void)
# endif
#endif
- /* Value-line devices don't implement flash prefetch/waitstates */
-
#ifndef CONFIG_STM32_VALUELINE
-
+ /* Value-line devices don't implement flash prefetch/waitstates */
/* Enable FLASH prefetch buffer and 2 wait states */
regval = getreg32(STM32_FLASH_ACR);
regval &= ~FLASH_ACR_LATENCY_MASK;
regval |= (FLASH_ACR_LATENCY_2|FLASH_ACR_PRTFBE);
putreg32(regval, STM32_FLASH_ACR);
-
#endif
/* Set the HCLK source/divider */
@@ -608,11 +617,9 @@ static void stm32_stdclockconfig(void)
regval |= STM32_RCC_CFGR_PPRE1;
putreg32(regval, STM32_RCC_CFGR);
- /* If we are using the PLL, configure and start it */
-
#if STM32_SYSCLK_SW == RCC_CFGR_SW_PLL
-
- /* Set the PLL divider and multipler */
+ /* If we are using the PLL, configure and start it */
+ /* Set the PLL divider and multiplier */
regval = getreg32(STM32_RCC_CFGR);
regval &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMUL_MASK);
@@ -641,6 +648,29 @@ static void stm32_stdclockconfig(void)
/* Wait until the selected source is used as the system clock source */
while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) != STM32_SYSCLK_SWS);
+
+#if defined(CONFIG_STM32_IWDG) || defined(CONFIG_RTC_LSICLOCK)
+ /* Low speed internal clock source LSI */
+ /*
+ * TODO: There is another case where the LSI needs to
+ * be enabled: if the MCO pin selects LSI as source.
+ */
+
+ stm32_rcc_enablelsi();
+#endif
+
+#if defined(CONFIG_RTC_LSECLOCK)
+ /* Low speed external clock source LSE
+ *
+ * TODO: There is another case where the LSE needs to
+ * be enabled: if the MCO pin selects LSE as source.
+ *
+ * TODO: There is another case where the LSE needs to
+ * be enabled: if USARTx selects LSE as source.
+ */
+
+ stm32_rcc_enablelse();
+#endif
}
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32f37xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f37xxx_rcc.c
index ddf3c5d9b..280915a4f 100644
--- a/nuttx/arch/arm/src/stm32/stm32f37xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f37xxx_rcc.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32f37xxx_rcc.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Modified for STM32F373 by Marten Svanfeldt <marten@svanfeldt.com>
*
@@ -39,7 +39,7 @@
****************************************************************************/
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
/* Allow up to 100 milliseconds for the high speed clock to become ready.
@@ -187,6 +187,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM2
/* Timer 2 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM2EN;
#endif
@@ -194,6 +195,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM3
/* Timer 3 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM3EN;
#endif
@@ -201,6 +203,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM4
/* Timer 4 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM4EN;
#endif
@@ -208,6 +211,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM5
/* Timer 5 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM4EN;
#endif
@@ -215,6 +219,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM6
/* Timer 6 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM6EN;
#endif
@@ -222,6 +227,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM7
/* Timer 7 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM7EN;
#endif
@@ -229,6 +235,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM12
/* Timer 12 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM12EN;
#endif
@@ -236,6 +243,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM13
/* Timer 13 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM13EN;
#endif
@@ -243,6 +251,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM14
/* Timer 14 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM14EN;
#endif
@@ -250,6 +259,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM18
/* Timer 7 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM18EN;
#endif
@@ -287,6 +297,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_I2C1
/* I2C 1 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_I2C1EN;
#endif
@@ -294,6 +305,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_I2C2
/* I2C 2 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_I2C2EN;
#endif
@@ -329,7 +341,6 @@ static inline void rcc_enableapb1(void)
regval |= RCC_APB1ENR_DAC1EN;
#endif
-
putreg32(regval, STM32_RCC_APB1ENR);
}
@@ -357,7 +368,6 @@ static inline void rcc_enableapb2(void)
regval |= RCC_APB2ENR_SYSCFGEN;
#endif
-
#ifdef CONFIG_STM32_SPI1
/* SPI 1 clock enable */
@@ -372,6 +382,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM15
/* TIM15 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM15EN;
#endif
@@ -379,6 +390,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM16
/* TIM16 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM16EN;
#endif
@@ -386,6 +398,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM17
/* TIM17 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM17EN;
#endif
@@ -393,6 +406,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM19
/* TIM17 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM17EN;
#endif
@@ -419,7 +433,6 @@ static void stm32_stdclockconfig(void)
/* If the PLL is using the HSE, or the HSE is the system clock */
#if (STM32_CFGR_PLLSRC == RCC_CFGR_PLLSRC) || (STM32_SYSCLK_SW == RCC_CFGR_SW_HSE)
-
{
volatile int32_t timeout;
@@ -455,6 +468,7 @@ static void stm32_stdclockconfig(void)
}
/* If this is a value-line part and we are using the HSE as the PLL */
+
# if (STM32_CFGR_PLLXTPRE >> 17) != (STM32_CFGR2_PREDIV1 & 1)
# error STM32_CFGR_PLLXTPRE must match the LSB of STM32_CFGR2_PREDIV1
# endif
@@ -466,7 +480,6 @@ static void stm32_stdclockconfig(void)
# endif
-
/* Enable FLASH prefetch buffer and 2 wait states */
regval = getreg32(STM32_FLASH_ACR);
@@ -474,7 +487,6 @@ static void stm32_stdclockconfig(void)
regval |= (FLASH_ACR_LATENCY_2|FLASH_ACR_PRTFBE);
putreg32(regval, STM32_FLASH_ACR);
-
/* Set the HCLK source/divider */
regval = getreg32(STM32_RCC_CFGR);
@@ -496,11 +508,9 @@ static void stm32_stdclockconfig(void)
regval |= STM32_RCC_CFGR_PPRE1;
putreg32(regval, STM32_RCC_CFGR);
- /* If we are using the PLL, configure and start it */
-
#if STM32_SYSCLK_SW == RCC_CFGR_SW_PLL
-
- /* Set the PLL divider and multipler */
+ /* If we are using the PLL, configure and start it */
+ /* Set the PLL divider and multiplier */
regval = getreg32(STM32_RCC_CFGR);
regval &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMUL_MASK);
@@ -529,6 +539,32 @@ static void stm32_stdclockconfig(void)
/* Wait until the selected source is used as the system clock source */
while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) != STM32_SYSCLK_SWS);
+
+#if defined(CONFIG_STM32_IWDG) || defined(CONFIG_RTC_LSICLOCK)
+ /* Low speed internal clock source LSI
+ *
+ * TODO: There is another case where the LSI needs to
+ * be enabled: if the MCO pin selects LSI as source.
+ */
+
+ stm32_rcc_enablelsi();
+#endif
+
+#if defined(CONFIG_RTC_LSECLOCK)
+ /* Low speed external clock source LSE
+ *
+ * TODO: There is another case where the LSE needs to
+ * be enabled: if the MCO pin selects LSE as source.
+ *
+ * TODO: There is another case where the LSE needs to
+ * be enabled: if USART1-2-3 selects LSE as source.
+ *
+ * TODO: There is another case where the LSE needs to
+ * be enabled: if CEC selects LSE as source.
+ */
+
+ stm32_rcc_enablelse();
+#endif
}
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
index 37e2ad81e..9721e906b 100644
--- a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32f40xxx_rcc.c
*
- * Copyright (C) 2011-2012, 2014 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012, 2014-2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -40,7 +40,7 @@
#include "stm32_pwr.h"
/****************************************************************************
- * Definitions
+ * Pre-processor Definitions
****************************************************************************/
/* Allow up to 100 milliseconds for the high speed clock to become ready.
@@ -458,7 +458,6 @@ static inline void rcc_enableapb1(void)
regval |= RCC_APB1ENR_UART8EN;
#endif
-
putreg32(regval, STM32_RCC_APB1ENR); /* Enable peripherals */
}
@@ -611,16 +610,17 @@ static void stm32_stdclockconfig(void)
/* Wait until the HSI is ready (or until a timeout elapsed) */
for (timeout = HSIRDY_TIMEOUT; timeout > 0; timeout--)
- {
- /* Check if the HSIRDY flag is the set in the CR */
+ {
+ /* Check if the HSIRDY flag is the set in the CR */
- if ((getreg32(STM32_RCC_CR) & RCC_CR_HSIRDY) != 0)
- {
- /* If so, then break-out with timeout > 0 */
+ if ((getreg32(STM32_RCC_CR) & RCC_CR_HSIRDY) != 0)
+ {
+ /* If so, then break-out with timeout > 0 */
+
+ break;
+ }
+ }
- break;
- }
- }
#else /* if STM32_BOARD_USEHSE */
/* Enable External High-Speed Clock (HSE) */
@@ -631,16 +631,16 @@ static void stm32_stdclockconfig(void)
/* Wait until the HSE is ready (or until a timeout elapsed) */
for (timeout = HSERDY_TIMEOUT; timeout > 0; timeout--)
- {
- /* Check if the HSERDY flag is the set in the CR */
+ {
+ /* Check if the HSERDY flag is the set in the CR */
- if ((getreg32(STM32_RCC_CR) & RCC_CR_HSERDY) != 0)
- {
- /* If so, then break-out with timeout > 0 */
+ if ((getreg32(STM32_RCC_CR) & RCC_CR_HSERDY) != 0)
+ {
+ /* If so, then break-out with timeout > 0 */
- break;
- }
- }
+ break;
+ }
+ }
#endif
/* Check for a timeout. If this timeout occurs, then we are hosed. We
@@ -785,6 +785,22 @@ static void stm32_stdclockconfig(void)
{
}
#endif
+
+#if defined(CONFIG_STM32_IWDG) || defined(CONFIG_RTC_LSICLOCK)
+ /* Low speed internal clock source LSI */
+
+ stm32_rcc_enablelsi();
+#endif
+
+#if defined(CONFIG_RTC_LSECLOCK)
+ /* Low speed external clock source LSE
+ *
+ * TODO: There is another case where the LSE needs to
+ * be enabled: if the MCO1 pin selects LSE as source.
+ */
+
+ stm32_rcc_enablelse();
+#endif
}
}
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32l15xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32l15xxx_rcc.c
index 0d3d77c80..af1bc1747 100644
--- a/nuttx/arch/arm/src/stm32/stm32l15xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32l15xxx_rcc.c
@@ -3,7 +3,7 @@
* For STM32L100xx, STM32L151xx, STM32L152xx and STM32L162xx advanced ARM-
* based 32-bit MCUs
*
- * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2013, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -51,6 +51,10 @@
#define HSERDY_TIMEOUT (100 * CONFIG_BOARD_LOOPSPERMSEC)
+/* HSE divisor to yield ~1MHz RTC clock (valid for HSE = 8MHz)*/
+
+#define HSE_DIVISOR RCC_CR_RTCPRE_HSEd8
+
/****************************************************************************
* Private Data
****************************************************************************/
@@ -236,6 +240,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM2
/* Timer 2 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM2EN;
#endif
@@ -243,6 +248,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM3
/* Timer 3 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM3EN;
#endif
@@ -250,6 +256,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM4
/* Timer 4 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM4EN;
#endif
@@ -257,6 +264,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM5
/* Timer 5 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM5EN;
#endif
@@ -264,6 +272,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM6
/* Timer 6 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM6EN;
#endif
@@ -271,6 +280,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_TIM7
/* Timer 7 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_TIM7EN;
#endif
@@ -334,6 +344,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_I2C1
/* I2C 1 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_I2C1EN;
#endif
@@ -341,6 +352,7 @@ static inline void rcc_enableapb1(void)
#ifdef CONFIG_STM32_I2C2
/* I2C 2 clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB1ENR_I2C2EN;
#endif
@@ -399,6 +411,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM9
/* TIM9 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM9EN;
#endif
@@ -406,6 +419,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM10
/* TIM10 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM10EN;
#endif
@@ -413,6 +427,7 @@ static inline void rcc_enableapb2(void)
#ifdef CONFIG_STM32_TIM11
/* TIM11 Timer clock enable */
+
#ifdef CONFIG_STM32_FORCEPOWER
regval |= RCC_APB2ENR_TIM11EN;
#endif
@@ -505,6 +520,9 @@ static inline bool stm32_rcc_enablehse(void)
static void stm32_stdclockconfig(void)
{
uint32_t regval;
+#if defined(CONFIG_RTC_HSECLOCK) || defined(CONFIG_LCD_HSECLOCK)
+ uint16_t pwrcr;
+#endif
/* Go to the high performance voltage range 1 if necessary. In this mode,
* the PLL VCO frequency can be up to 96MHz. USB and SDIO can be supported.
@@ -518,6 +536,42 @@ static void stm32_stdclockconfig(void)
stm32_pwr_setvos(PWR_CR_VOS_SCALE_1);
#endif
+#if defined(CONFIG_RTC_HSECLOCK) || defined(CONFIG_LCD_HSECLOCK)
+ /* If RTC / LCD selects HSE as clock source, the RTC prescaler
+ * needs to be set before HSEON bit is set.
+ */
+
+ /* The RTC domain has write access denied after reset,
+ * you have to enable write access using DBP bit in the PWR CR
+ * register before to selecting the clock source ( and the PWR
+ * peripheral must be enabled)
+ */
+
+ regval = getreg32(STM32_RCC_APB1ENR);
+ regval |= RCC_APB1ENR_PWREN;
+ putreg32(regval, STM32_RCC_APB1ENR);
+
+ pwrcr = getreg16(STM32_PWR_CR);
+ putreg16(pwrcr | PWR_CR_DBP, STM32_PWR_CR);
+
+ /* Set the RTC clock divisor */
+
+ regval = getreg32(STM32_RCC_CSR);
+ regval &= ~RCC_CSR_RTCSEL_MASK;
+ regval |= RCC_CSR_RTCSEL_HSE;
+ putreg32(regval, STM32_RCC_CSR);
+
+ regval = getreg32(STM32_RCC_CR);
+ regval &= ~RCC_CR_RTCPRE_MASK;
+ regval |= HSE_DIVISOR);
+ putreg32(regval, STM32_RCC_CR);
+
+ /* Restore the previous state of the DBP bit */
+
+ putreg32(regval, STM32_PWR_CR);
+
+#endif
+
/* Enable the source clock for the PLL (via HSE or HSI), HSE, and HSI.
* NOTE that only PLL, HSE, or HSI are supported for the system clock
* in this implementation
@@ -615,7 +669,7 @@ static void stm32_stdclockconfig(void)
#if STM32_SYSCLK_SW == RCC_CFGR_SW_PLL
- /* Set the PLL divider and multipler. NOTE: The PLL needs to be disabled
+ /* Set the PLL divider and multiplier. NOTE: The PLL needs to be disabled
* to do these operation. We know this is the case here because pll_reset()
* was previously called by stm32_clockconfig().
*/
@@ -647,6 +701,35 @@ static void stm32_stdclockconfig(void)
/* Wait until the selected source is used as the system clock source */
while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) != STM32_SYSCLK_SWS);
+
+#if defined(CONFIG_STM32_IWDG) || \
+ defined(CONFIG_RTC_LSICLOCK) || defined(CONFIG_LCD_LSICLOCK)
+ /* Low speed internal clock source LSI */
+ /*
+ * TODO: There is another case where the LSI needs to
+ * be enabled: if the MCO pin selects LSI as source.
+ */
+
+ stm32_rcc_enablelsi();
+
+#endif
+
+#if defined(CONFIG_RTC_LSECLOCK) || defined(CONFIG_LCD_LSECLOCK)
+ /* Low speed external clock source LSE
+ *
+ * TODO: There is another case where the LSE needs to
+ * be enabled: if the MCO pin selects LSE as source.
+ *
+ * TODO: There is another case where the LSE needs to
+ * be enabled: if TIM9-10 Channel 1 selects LSE as input.
+ *
+ * TODO: There is another case where the LSE needs to
+ * be enabled: if TIM10-11 selects LSE as ETR Input.
+ *
+ */
+
+ stm32_rcc_enablelse();
+#endif
}
#endif