aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--include/libopencm3/stm32/l1/rcc.h43
-rw-r--r--lib/stm32/l1/Makefile6
-rw-r--r--lib/stm32/l1/pwr_chipset.c37
-rw-r--r--lib/stm32/l1/rcc.c121
4 files changed, 192 insertions, 15 deletions
diff --git a/include/libopencm3/stm32/l1/rcc.h b/include/libopencm3/stm32/l1/rcc.h
index 6c7dc95..21b073b 100644
--- a/include/libopencm3/stm32/l1/rcc.h
+++ b/include/libopencm3/stm32/l1/rcc.h
@@ -46,6 +46,7 @@ LGPL License Terms @ref lgpl_license
#include <libopencm3/stm32/memorymap.h>
#include <libopencm3/cm3/common.h>
+#include <libopencm3/stm32/l1/pwr.h>
/* --- RCC registers ------------------------------------------------------- */
@@ -110,6 +111,8 @@ LGPL License Terms @ref lgpl_license
#define RCC_CFGR_PLLDIV_DIV2 0x1
#define RCC_CFGR_PLLDIV_DIV3 0x2
#define RCC_CFGR_PLLDIV_DIV4 0x3
+#define RCC_CFGR_PLLDIV_SHIFT 22
+#define RCC_CFGR_PLLDIV_MASK 0x3
/* PLLMUL: PLL multiplication factor */
#define RCC_CFGR_PLLMUL_MUL3 0x0
@@ -121,6 +124,8 @@ LGPL License Terms @ref lgpl_license
#define RCC_CFGR_PLLMUL_MUL24 0x6
#define RCC_CFGR_PLLMUL_MUL32 0x7
#define RCC_CFGR_PLLMUL_MUL48 0x8
+#define RCC_CFGR_PLLMUL_SHIFT 18
+#define RCC_CFGR_PLLMUL_MASK 0xf
/* PLLSRC: PLL entry clock source */
#define RCC_CFGR_PLLSRC_HSI_CLK 0x0
@@ -349,6 +354,28 @@ LGPL License Terms @ref lgpl_license
#define RCC_CSR_LSIRDY (1 << 1)
#define RCC_CSR_LSION (1 << 0)
+typedef struct {
+ uint8_t pll_mul;
+ uint16_t pll_div;
+ uint8_t pll_source;
+ uint32_t flash_config;
+ uint8_t hpre;
+ uint8_t ppre1;
+ uint8_t ppre2;
+ vos_scale_t voltage_scale;
+ uint32_t apb1_frequency;
+ uint32_t apb2_frequency;
+} clock_scale_t;
+
+typedef enum {
+ CLOCK_VRANGE1_HSI_PLL_24MHZ,
+ CLOCK_VRANGE1_HSI_PLL_32MHZ,
+ CLOCK_VRANGE1_HSI_RAW_16MHZ,
+ CLOCK_VRANGE1_END
+} clock_volt_range1_t;
+
+extern const clock_scale_t clock_vrange1_config[CLOCK_VRANGE1_END];
+
/* --- Variable definitions ------------------------------------------------ */
extern u32 rcc_ppre1_frequency;
@@ -378,26 +405,16 @@ void rcc_peripheral_disable_clock(volatile u32 *reg, u32 en);
void rcc_peripheral_reset(volatile u32 *reg, u32 reset);
void rcc_peripheral_clear_reset(volatile u32 *reg, u32 clear_reset);
void rcc_set_sysclk_source(u32 clk);
-void rcc_set_pll_multiplication_factor(u32 mul);
+void rcc_set_pll_configuration(u32 source, u32 multiplier, u32 divisor);
void rcc_set_pll_source(u32 pllsrc);
-void rcc_set_pllxtpre(u32 pllxtpre);
void rcc_set_adcpre(u32 adcpre);
void rcc_set_ppre2(u32 ppre2);
void rcc_set_ppre1(u32 ppre1);
void rcc_set_hpre(u32 hpre);
void rcc_set_usbpre(u32 usbpre);
u32 rcc_get_system_clock_source(int i);
-void rcc_clock_setup_in_hsi_out_64mhz(void);
-void rcc_clock_setup_in_hsi_out_48mhz(void);
-
-/**
- * Maximum speed possible for F100 (Value Line) on HSI
- */
-void rcc_clock_setup_in_hsi_out_24mhz(void);
-void rcc_clock_setup_in_hse_8mhz_out_24mhz(void);
-void rcc_clock_setup_in_hse_8mhz_out_72mhz(void);
-void rcc_clock_setup_in_hse_12mhz_out_72mhz(void);
-void rcc_clock_setup_in_hse_16mhz_out_72mhz(void);
+void rcc_clock_setup_hsi(const clock_scale_t *clock);
+void rcc_clock_setup_pll(const clock_scale_t *clock);
void rcc_backupdomain_reset(void);
/**@}*/
diff --git a/lib/stm32/l1/Makefile b/lib/stm32/l1/Makefile
index dc587c2..cecc95c 100644
--- a/lib/stm32/l1/Makefile
+++ b/lib/stm32/l1/Makefile
@@ -28,8 +28,10 @@ CFLAGS = -Os -g -Wall -Wextra -I../../../include -fno-common \
-ffunction-sections -fdata-sections -MD -DSTM32L1
# ARFLAGS = rcsv
ARFLAGS = rcs
-OBJS = rcc.o gpio.o desig.o crc.o usart.o exti2.o \
- flash.o gpio_common_all.o gpio_common_f24.o
+OBJS = rcc.o gpio.o desig.o crc.o usart.o exti2.o
+OBJS += flash.o gpio_common_all.o gpio_common_f24.o
+OBJS += pwr_chipset.o # TODO, get pwr.o to fix f2/f4 first... pwr.o
+#OBJS += timer.o # WORK IN PROGRESS
VPATH += ../../usb:../:../../cm3:../common
diff --git a/lib/stm32/l1/pwr_chipset.c b/lib/stm32/l1/pwr_chipset.c
new file mode 100644
index 0000000..9f4f599
--- /dev/null
+++ b/lib/stm32/l1/pwr_chipset.c
@@ -0,0 +1,37 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopencm3/stm32/l1/pwr.h>
+
+void pwr_set_vos_scale(vos_scale_t scale)
+{
+ PWR_CR &= ~(PWR_CR_VOS_MASK);
+ switch (scale) {
+ case RANGE1:
+ PWR_CR |= PWR_CR_VOS_RANGE1;
+ break;
+ case RANGE2:
+ PWR_CR |= PWR_CR_VOS_RANGE2;
+ break;
+ case RANGE3:
+ PWR_CR |= PWR_CR_VOS_RANGE3;
+ break;
+ }
+}
+
diff --git a/lib/stm32/l1/rcc.c b/lib/stm32/l1/rcc.c
index a023622..bbba9a9 100644
--- a/lib/stm32/l1/rcc.c
+++ b/lib/stm32/l1/rcc.c
@@ -22,11 +22,50 @@
*/
#include <libopencm3/stm32/l1/rcc.h>
+#include <libopencm3/stm32/l1/flash.h>
+#include <libopencm3/stm32/l1/pwr.h>
/* Set the default ppre1 and ppre2 peripheral clock frequencies after reset. */
u32 rcc_ppre1_frequency = 2097000;
u32 rcc_ppre2_frequency = 2097000;
+const clock_scale_t clock_vrange1_config[CLOCK_VRANGE1_END] =
+{
+ { /* 24MHz PLL from HSI */
+ .pll_source = RCC_CFGR_PLLSRC_HSI_CLK,
+ .pll_mul = RCC_CFGR_PLLMUL_MUL3,
+ .pll_div = RCC_CFGR_PLLDIV_DIV2,
+ .hpre = RCC_CFGR_HPRE_SYSCLK_NODIV,
+ .ppre1 = RCC_CFGR_PPRE1_HCLK_NODIV,
+ .ppre2 = RCC_CFGR_PPRE2_HCLK_NODIV,
+ .voltage_scale = RANGE1,
+ .flash_config = FLASH_LATENCY_1WS,
+ .apb1_frequency = 24000000,
+ .apb2_frequency = 24000000,
+ },
+ { /* 32MHz PLL from HSI */
+ .pll_source = RCC_CFGR_PLLSRC_HSI_CLK,
+ .pll_mul = RCC_CFGR_PLLMUL_MUL6,
+ .pll_div = RCC_CFGR_PLLDIV_DIV3,
+ .hpre = RCC_CFGR_HPRE_SYSCLK_NODIV,
+ .ppre1 = RCC_CFGR_PPRE1_HCLK_NODIV,
+ .ppre2 = RCC_CFGR_PPRE2_HCLK_NODIV,
+ .voltage_scale = RANGE1,
+ .flash_config = FLASH_LATENCY_1WS,
+ .apb1_frequency = 32000000,
+ .apb2_frequency = 32000000,
+ },
+ { /* 16MHz HSI raw */
+ .hpre = RCC_CFGR_HPRE_SYSCLK_NODIV,
+ .ppre1 = RCC_CFGR_PPRE1_HCLK_NODIV,
+ .ppre2 = RCC_CFGR_PPRE2_HCLK_NODIV,
+ .voltage_scale = RANGE1,
+ .flash_config = FLASH_LATENCY_0WS,
+ .apb1_frequency = 16000000,
+ .apb2_frequency = 16000000,
+ },
+};
+
void rcc_osc_ready_int_clear(osc_t osc)
{
switch (osc) {
@@ -304,6 +343,20 @@ void rcc_set_sysclk_source(u32 clk)
RCC_CFGR = (reg32 | clk);
}
+void rcc_set_pll_configuration(u32 source, u32 multiplier, u32 divisor)
+{
+ u32 reg32;
+
+ reg32 = RCC_CFGR;
+ reg32 &= ~(RCC_CFGR_PLLDIV_MASK << RCC_CFGR_PLLDIV_SHIFT);
+ reg32 &= ~(RCC_CFGR_PLLMUL_MASK << RCC_CFGR_PLLMUL_SHIFT);
+ reg32 &= ~(1 << 16);
+ reg32 |= (source << 16);
+ reg32 |= (multiplier << RCC_CFGR_PLLMUL_SHIFT);
+ reg32 |= (divisor << RCC_CFGR_PLLDIV_SHIFT);
+ RCC_CFGR = reg32;
+}
+
void rcc_set_pll_source(u32 pllsrc)
{
u32 reg32;
@@ -355,3 +408,71 @@ u32 rcc_system_clock_source(void)
return ((RCC_CFGR & 0x000c) >> 2);
}
+void rcc_clock_setup_hsi(const clock_scale_t *clock)
+{
+ /* Enable internal high-speed oscillator. */
+ rcc_osc_on(HSI);
+ rcc_wait_for_osc_ready(HSI);
+
+ /* Select HSI as SYSCLK source. */
+ rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_HSICLK);
+
+ /*
+ * Set prescalers for AHB, ADC, ABP1, ABP2.
+ * Do this before touching the PLL (TODO: why?).
+ */
+ rcc_set_hpre(clock->hpre);
+ rcc_set_ppre1(clock->ppre1);
+ rcc_set_ppre2(clock->ppre2);
+
+ pwr_set_vos_scale(clock->voltage_scale);
+
+ // I guess this should be in the settings?
+ flash_64bit_enable();
+ flash_prefetch_enable();
+ /* Configure flash settings. */
+ flash_set_ws(clock->flash_config);
+
+ /* Set the peripheral clock frequencies used. */
+ rcc_ppre1_frequency = clock->apb1_frequency;
+ rcc_ppre2_frequency = clock->apb2_frequency;
+}
+
+void rcc_clock_setup_pll(const clock_scale_t *clock)
+{
+ /* Enable internal high-speed oscillator. */
+ rcc_osc_on(HSI);
+ rcc_wait_for_osc_ready(HSI);
+
+ /* Select HSI as SYSCLK source. */
+ rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_HSICLK);
+
+ /*
+ * Set prescalers for AHB, ADC, ABP1, ABP2.
+ * Do this before touching the PLL (TODO: why?).
+ */
+ rcc_set_hpre(clock->hpre);
+ rcc_set_ppre1(clock->ppre1);
+ rcc_set_ppre2(clock->ppre2);
+
+ pwr_set_vos_scale(clock->voltage_scale);
+
+ // I guess this should be in the settings?
+ flash_64bit_enable();
+ flash_prefetch_enable();
+ /* Configure flash settings. */
+ flash_set_ws(clock->flash_config);
+
+ rcc_set_pll_configuration(clock->pll_source, clock->pll_mul, clock->pll_div);
+
+ /* Enable PLL oscillator and wait for it to stabilize. */
+ rcc_osc_on(PLL);
+ rcc_wait_for_osc_ready(PLL);
+
+ /* Select PLL as SYSCLK source. */
+ rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_PLLCLK);
+
+ /* Set the peripheral clock frequencies used. */
+ rcc_ppre1_frequency = clock->apb1_frequency;
+ rcc_ppre2_frequency = clock->apb2_frequency;
+}