summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f40xxx_rcc.h4
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_rtcc.c54
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c9
3 files changed, 52 insertions, 15 deletions
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_rcc.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_rcc.h
index 8ab09c478..86c3b33cb 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_rcc.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_rcc.h
@@ -182,8 +182,8 @@
# define RCC_CFGR_PPRE2_HCLKd8 (6 << RCC_CFGR_PPRE2_SHIFT) /* 110: HCLK divided by 8 */
# define RCC_CFGR_PPRE2_HCLKd16 (7 << RCC_CFGR_PPRE2_SHIFT) /* 111: HCLK divided by 16 */
#define RCC_CFGR_RTCPRE_SHIFT (16) /* Bits 16-20: APB High speed prescaler (APB2) */
-#define RCC_CFGR_RTCPRE_MASK (31 << RCC_CFGR_RTCPRE)
-# define RCC_CFGR_RTCPRE(n) ((n) << RCC_CFGR_RTCPRE) /* HSE/n, n=1..31 */
+#define RCC_CFGR_RTCPRE_MASK (31 << RCC_CFGR_RTCPRE_SHIFT)
+# define RCC_CFGR_RTCPRE(n) ((n) << RCC_CFGR_RTCPRE_SHIFT) /* HSE/n, n=1..31 */
#define RCC_CFGR_MCO1_SHIFT (21) /* Bits 21-22: Microcontroller Clock Output */
#define RCC_CFGR_MCO1_MASK (3 << RCC_CFGR_MCO1_SHIFT)
# define RCC_CFGR_MCO1_HSI (0 << RCC_CFGR_MCO1_SHIFT) /* 00: HSI clock selected */
diff --git a/nuttx/arch/arm/src/stm32/stm32_rtcc.c b/nuttx/arch/arm/src/stm32/stm32_rtcc.c
index e9e71a007..6ba69e295 100644
--- a/nuttx/arch/arm/src/stm32/stm32_rtcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_rtcc.c
@@ -81,9 +81,7 @@
#define SYNCHRO_TIMEOUT (0x00020000)
#define INITMODE_TIMEOUT (0x00010000)
-#define RTC_MAGIC (0xfacefeed)
-#define RTC_PREDIV_S (0xff)
-#define RTC_PREDIV_A (0x7f)
+#define RTC_MAGIC (0xfacefeee)
/* Debug ****************************************************************************/
@@ -437,11 +435,30 @@ static int rtc_setup(void)
uint32_t regval;
int ret;
- /* Enable the External Low-Speed (LSE) Oscillator setup the LSE as the RTC clock\
- * source, and enable the RTC.
- */
+ /* 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)
+ 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
stm32_rcc_enablelse();
+#endif
/* Wait for the RTC Time and Date registers to be synchronized with RTC APB
* clock.
@@ -467,13 +484,19 @@ static int rtc_setup(void)
regval &= ~RTC_CR_FMT;
putreg32(regval, STM32_RTC_CR);
- /* Configure RTC pre-scaler to the required, default values for
- * use with the 32.768 KHz LSE clock:
- */
+ /* 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 */
+ 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 */
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 */
@@ -576,8 +599,6 @@ int up_rtcinitialize(void)
uint32_t regval;
int ret;
- rtc_dumpregs("On reset");
-
/* Clocking for the PWR block must be provided. However, this is done
* unconditionally in stm32f40xxx_rcc.c on power up. This done unconditionally
* because the PWR block is also needed to set the internal voltage regulator for
@@ -590,11 +611,16 @@ int up_rtcinitialize(void)
stm32_pwr_enablebkp();
- /* Check if the one-time initialization of the RTC has already been performed.
+ rtc_dumpregs("On reset");
+
+ /* Enable the External Low-Speed (LSE) Oscillator setup the LSE as the RTC clock\
+ * source, and enable the RTC.
+ */
+
+ /* Check if the one-time initialization of the RTC has already been perfomagrmed.
* We can determine this by checking if the magic number has been writing to
* to back-up date register DR0.
*/
-
regval = getreg32(STM32_RTC_BK0R);
if (regval != RTC_MAGIC)
{
@@ -611,6 +637,8 @@ int up_rtcinitialize(void)
/* RTC already set-up, just resume normal operation */
ret = rtc_resume();
+
+ rtc_dumpregs("Did resume");
}
/* Configure RTC interrupt to catch alarm interrupts. All RTC interrupts are
diff --git a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
index 82757c43f..4eef64801 100644
--- a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
@@ -651,6 +651,15 @@ static void stm32_stdclockconfig(void)
regval |= STM32_RCC_CFGR_PPRE1;
putreg32(regval, STM32_RCC_CFGR);
+#ifdef CONFIG_RTC_HSECLOCK
+ /* Set the RTC clock divisor */
+
+ regval = getreg32(STM32_RCC_CFGR);
+ regval &= ~RCC_CFGR_RTCPRE_MASK;
+ regval |= RCC_CFGR_RTCPRE(24); /* Assume 24MHz ext clock */
+ putreg32(regval, STM32_RCC_CFGR);
+#endif
+
/* Set the PLL dividers and multiplers to configure the main PLL */
regval = (STM32_PLLCFG_PLLM | STM32_PLLCFG_PLLN |STM32_PLLCFG_PLLP |