summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-05-20 15:51:37 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-05-20 15:51:37 -0600
commit921386a847b6e610223d808f1ba718c6518ff403 (patch)
tree07caa807a4e96c623e3048287ea4c6403195acd4 /nuttx/arch/arm
parent624f28e66b785245650c96e6ca2375cf37f505ff (diff)
downloadpx4-nuttx-921386a847b6e610223d808f1ba718c6518ff403.tar.gz
px4-nuttx-921386a847b6e610223d808f1ba718c6518ff403.tar.bz2
px4-nuttx-921386a847b6e610223d808f1ba718c6518ff403.zip
STM32L152: Better LOOPSPERMSEC; Need to set higher performance VOS
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_pwr.h6
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_lowputc.c2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_pwr.c53
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_pwr.h27
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c1
-rw-r--r--nuttx/arch/arm/src/stm32/stm32l15xxx_rcc.c25
6 files changed, 100 insertions, 14 deletions
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h b/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h
index 9f1220ba9..430624d3b 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h
@@ -108,9 +108,9 @@
# define PWR_CR_ULP (1 << 9) /* Ultralow power mode */
# define PWR_CR_FWU (1 << 10) /* Low power run mode */
# define PWR_CR_VOS_MASK (3 << 11) /* Bits 11-12: Regulator voltage scaling output selection */
-# define PWR_CR_VOS_SCALE_1 (1 << 11) /* 1.8 V (range 1) */
-# define PWR_CR_VOS_SCALE_2 (2 << 11) /* 1.5 V (range 2) */
-# define PWR_CR_VOS_SCALE_3 (3 << 11) /* 1.2 V (range 3) */
+# define PWR_CR_VOS_SCALE_1 (1 << 11) /* 1.8 V (range 1) PLL VCO Max = 96MHz */
+# define PWR_CR_VOS_SCALE_2 (2 << 11) /* 1.5 V (range 2) PLL VCO Max = 64MHz */
+# define PWR_CR_VOS_SCALE_3 (3 << 11) /* 1.2 V (range 3) PLL VCO Max = 24MHz */
# define PWR_CR_LPRUN (1 << 14) /* Low power run mode */
#endif
diff --git a/nuttx/arch/arm/src/stm32/stm32_lowputc.c b/nuttx/arch/arm/src/stm32/stm32_lowputc.c
index 49ac15e9a..f733aad80 100644
--- a/nuttx/arch/arm/src/stm32/stm32_lowputc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_lowputc.c
@@ -621,5 +621,3 @@ void stm32_lowsetup(void)
#else
# error "Unsupported STM32 chip"
#endif
-
-
diff --git a/nuttx/arch/arm/src/stm32/stm32_pwr.c b/nuttx/arch/arm/src/stm32/stm32_pwr.c
index 14149922f..1c9513541 100644
--- a/nuttx/arch/arm/src/stm32/stm32_pwr.c
+++ b/nuttx/arch/arm/src/stm32/stm32_pwr.c
@@ -2,7 +2,9 @@
* arch/arm/src/stm32/stm32_pwr.c
*
* Copyright (C) 2011 Uros Platise. All rights reserved.
- * Author: Uros Platise <uros.platise@isotel.eu>
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Authors: Uros Platise <uros.platise@isotel.eu>
+ * Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -58,17 +60,17 @@
static inline uint16_t stm32_pwr_getreg(uint8_t offset)
{
- return getreg32(STM32_PWR_BASE + offset);
+ return (uint16_t)getreg32(STM32_PWR_BASE + (uint32_t)offset);
}
static inline void stm32_pwr_putreg(uint8_t offset, uint16_t value)
{
- putreg32(value, STM32_PWR_BASE + offset);
+ putreg32((uint32_t)value, STM32_PWR_BASE + (uint32_t)offset);
}
static inline void stm32_pwr_modifyreg(uint8_t offset, uint16_t clearbits, uint16_t setbits)
{
- modifyreg32(STM32_PWR_BASE + offset, clearbits, setbits);
+ modifyreg32(STM32_PWR_BASE + (uint32_t)offset, (uint32_t)clearbits, (uint32_t)setbits);
}
/************************************************************************************
@@ -95,4 +97,47 @@ void stm32_pwr_enablebkp(void)
stm32_pwr_modifyreg(STM32_PWR_CR_OFFSET, 0, PWR_CR_DBP);
}
+/************************************************************************************
+ * Name: stm32_pwr_setvos
+ *
+ * Description:
+ * Set voltage scaling for EneryLite devices.
+ *
+ * Input Parameters:
+ * vos - Properly aligned voltage scaling select bits for the PWR_CR register.
+ *
+ * Returned Values:
+ * None
+ *
+ * Assumptions:
+ * At present, this function is called only from initialization logic. If used
+ * for any other purpose that protection to assure that its operation is atomic
+ * will be required.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_ENERGYLITE
+void stm32_pwr_setvos(uint16_t vos)
+{
+ uint16_t regval;
+
+ /* The following sequence is required to program the voltage regulator ranges:
+ * 1. Check VDD to identify which ranges are allowed...
+ * 2. Poll VOSF bit of in PWR_CSR. Wait until it is reset to 0.
+ * 3. Configure the voltage scaling range by setting the VOS bits in the PWR_CR
+ * register.
+ * 4. Poll VOSF bit of in PWR_CSR register. Wait until it is reset to 0.
+ */
+
+ while((stm32_pwr_getreg(STM32_PWR_CSR_OFFSET) & PWR_CSR_VOSF) != 0);
+
+ regval = stm32_pwr_getreg(STM32_PWR_CR_OFFSET);
+ regval &= ~PWR_CR_VOS_MASK;
+ regval |= (vos & PWR_CR_VOS_MASK);
+ stm32_pwr_putreg(STM32_PWR_CR_OFFSET, regval);
+
+ while((stm32_pwr_getreg(STM32_PWR_CSR_OFFSET) & PWR_CSR_VOSF) != 0);
+}
+#endif
+
#endif /* CONFIG_STM32_PWR */
diff --git a/nuttx/arch/arm/src/stm32/stm32_pwr.h b/nuttx/arch/arm/src/stm32/stm32_pwr.h
index 7a2751677..63ae14429 100644
--- a/nuttx/arch/arm/src/stm32/stm32_pwr.h
+++ b/nuttx/arch/arm/src/stm32/stm32_pwr.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_pwr.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -78,7 +78,30 @@ extern "C" {
*
************************************************************************************/
-EXTERN void stm32_pwr_enablebkp(void);
+void stm32_pwr_enablebkp(void);
+
+/************************************************************************************
+ * Name: stm32_pwr_setvos
+ *
+ * Description:
+ * Set voltage scaling for EneryLite devices.
+ *
+ * Input Parameters:
+ * vos - Properly aligned voltage scaling select bits for the PWR_CR register.
+ *
+ * Returned Values:
+ * None
+ *
+ * Assumptions:
+ * At present, this function is called only from initialization logic. If used
+ * for any other purpose that protection to assure that its operation is atomic
+ * will be required.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_ENERGYLITE
+void stm32_pwr_setvos(uint16_t vos);
+#endif
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index 4a06faee6..af95244f0 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -1214,6 +1214,7 @@ static void up_setspeed(struct uart_dev_s *dev)
static int up_setup(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+
#ifndef CONFIG_SUPPRESS_UART_CONFIG
uint32_t regval;
diff --git a/nuttx/arch/arm/src/stm32/stm32l15xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32l15xxx_rcc.c
index e8895dd89..1063c27c1 100644
--- a/nuttx/arch/arm/src/stm32/stm32l15xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32l15xxx_rcc.c
@@ -1,5 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32l15xxx_rcc.c
+ * For STM32L100xx, STM32L151xx, STM32L152xx and STM32L162xx advanced ARM-
+ * based 32-bit MCUs
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -134,7 +136,11 @@ static inline void rcc_reset(void)
putreg32(0, STM32_RCC_CIR); /* Disable all interrupts */
- /* Rest the FLASH controller to 32-bit mode, no wait states.
+ /* Go to the (default) voltage range 2 */
+
+ stm32_pwr_setvos(PWR_CR_VOS_SCALE_2);
+
+ /* Reset the FLASH controller to 32-bit mode, no wait states.
*
* First, program the new number of WS to the LATENCY bit in Flash access
* control register (FLASH_ACR)
@@ -490,8 +496,21 @@ static void stm32_stdclockconfig(void)
{
uint32_t regval;
- /* First, enable the source clock only the PLL (via HSE or HSI), HSE, and HSI
- * are supported in this implementation.
+ /* 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.
+ *
+ * Range 1: PLLVCO up to 96MHz in range 1 (1.8V)
+ * Range 2: PLLVCO up to 48MHz in range 2 (1.5V)
+ * Range 3: PLLVCO up to 24MHz in range 3 (1.2V)
+ */
+
+#if STM32_PLL_FREQUENCY > 48000000
+ stm32_pwr_setvos(PWR_CR_VOS_SCALE_1);
+#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
*/
#if (STM32_CFGR_PLLSRC == RCC_CFGR_PLLSRC) || (STM32_SYSCLK_SW == RCC_CFGR_SW_HSE)