aboutsummaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
authorPerry Hung <iperry@gmail.com>2011-03-21 02:25:23 -0400
committerPerry Hung <iperry@gmail.com>2011-03-21 02:25:23 -0400
commit403498a28956507bb3063e6d7c190639c0279f47 (patch)
treed68ccd6e85ac82bea1dff4066ad7fbd8003bdecb
parent6245b43b26e47ece1927d28246611488c2f36e67 (diff)
downloadlibrambutan-403498a28956507bb3063e6d7c190639c0279f47.tar.gz
librambutan-403498a28956507bb3063e6d7c190639c0279f47.zip
Revert "RCC refactor, bugfixes"
This reverts commit e4807a5010f59ab863ad2c96dc14caf65bf1ae60.
-rw-r--r--libmaple/adc.c4
-rw-r--r--libmaple/adc.h6
-rw-r--r--libmaple/bkp.c4
-rw-r--r--libmaple/dac.c4
-rw-r--r--libmaple/dac.h4
-rw-r--r--libmaple/exti.c18
-rw-r--r--libmaple/gpio.c2
-rw-r--r--libmaple/rcc.c200
-rw-r--r--libmaple/rcc.h541
-rw-r--r--wirish/boards.cpp2
-rw-r--r--wirish/wirish.cpp2
11 files changed, 212 insertions, 575 deletions
diff --git a/libmaple/adc.c b/libmaple/adc.c
index 3d38596..9626a40 100644
--- a/libmaple/adc.c
+++ b/libmaple/adc.c
@@ -126,8 +126,8 @@ void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate) {
* @param dev adc device
*/
static void adc_calibrate(const adc_dev *dev) {
- __io uint32 *rstcal_bit = bb_perip(&(dev->regs->CR2), 3);
- __io uint32 *cal_bit = bb_perip(&(dev->regs->CR2), 2);
+ __io uint32 *rstcal_bit = bb_peripv(&(dev->regs->CR2), 3);
+ __io uint32 *cal_bit = bb_peripv(&(dev->regs->CR2), 2);
*rstcal_bit = 1;
while (*rstcal_bit)
diff --git a/libmaple/adc.h b/libmaple/adc.h
index 53ef032..4811dbc 100644
--- a/libmaple/adc.h
+++ b/libmaple/adc.h
@@ -175,7 +175,7 @@ static inline uint32 adc_read(const adc_dev *dev, uint8 channel) {
* @param enable If 1, conversion on external events is enabled, 0 to disable
*/
static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) {
- *bb_perip(&dev->regs->CR2, 20) = !!enable;
+ *bb_peripv(&dev->regs->CR2, 20) = !!enable;
}
/**
@@ -183,7 +183,7 @@ static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) {
* @param dev ADC device to enable
*/
static inline void adc_enable(const adc_dev *dev) {
- *bb_perip(&dev->regs->CR2, 0) = 1;
+ *bb_peripv(&dev->regs->CR2, 0) = 1;
}
/**
@@ -191,7 +191,7 @@ static inline void adc_enable(const adc_dev *dev) {
* @param dev ADC device to disable
*/
static inline void adc_disable(const adc_dev *dev) {
- *bb_perip(&dev->regs->CR2, 0) = 0;
+ *bb_peripv(&dev->regs->CR2, 0) = 0;
}
/**
diff --git a/libmaple/bkp.c b/libmaple/bkp.c
index aaccb1f..b152069 100644
--- a/libmaple/bkp.c
+++ b/libmaple/bkp.c
@@ -57,14 +57,14 @@ void bkp_init(void) {
* @see bkp_init()
*/
void bkp_enable_writes(void) {
- *bb_perip(&PWR_BASE->CR, PWR_CR_DBP) = 1;
+ *bb_peripv(&PWR_BASE->CR, PWR_CR_DBP) = 1;
}
/**
* Disable write access to the backup registers.
*/
void bkp_disable_writes(void) {
- *bb_perip(&PWR_BASE->CR, PWR_CR_DBP) = 0;
+ *bb_peripv(&PWR_BASE->CR, PWR_CR_DBP) = 0;
}
/**
diff --git a/libmaple/dac.c b/libmaple/dac.c
index f0bdbcd..ef3a9f9 100644
--- a/libmaple/dac.c
+++ b/libmaple/dac.c
@@ -26,8 +26,6 @@
#include "gpio.h"
#include "dac.h"
-#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
-
/**
* @brief DAC peripheral routines.
*/
@@ -110,5 +108,3 @@ void dac_disable_channel(uint8 channel) {
break;
}
}
-
-#endif
diff --git a/libmaple/dac.h b/libmaple/dac.h
index ee8a4e7..c897bb2 100644
--- a/libmaple/dac.h
+++ b/libmaple/dac.h
@@ -32,8 +32,6 @@
#ifndef _DAC_H_
#define _DAC_H_
-#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
-
#include "rcc.h"
#ifdef __cplusplus
@@ -151,6 +149,4 @@ void dac_disable_channel(uint8 channel);
} // extern "C"
#endif
-#endif /* STM32_HIGH_DENSITY, STM32_XL_DENSITY */
-
#endif
diff --git a/libmaple/exti.c b/libmaple/exti.c
index 7f56712..8177e1e 100644
--- a/libmaple/exti.c
+++ b/libmaple/exti.c
@@ -98,14 +98,14 @@ void exti_attach_interrupt(afio_exti_num num,
/* Set trigger mode */
switch (mode) {
case EXTI_RISING:
- *bb_perip(&EXTI_BASE->RTSR, num) = 1;
+ *bb_peripv(&EXTI_BASE->RTSR, num) = 1;
break;
case EXTI_FALLING:
- *bb_perip(&EXTI_BASE->FTSR, num) = 1;
+ *bb_peripv(&EXTI_BASE->FTSR, num) = 1;
break;
case EXTI_RISING_FALLING:
- *bb_perip(&EXTI_BASE->RTSR, num) = 1;
- *bb_perip(&EXTI_BASE->FTSR, num) = 1;
+ *bb_peripv(&EXTI_BASE->RTSR, num) = 1;
+ *bb_peripv(&EXTI_BASE->FTSR, num) = 1;
break;
}
@@ -113,7 +113,7 @@ void exti_attach_interrupt(afio_exti_num num,
afio_exti_select(num, port);
/* Unmask external interrupt request */
- *bb_perip(&EXTI_BASE->IMR, num) = 1;
+ *bb_peripv(&EXTI_BASE->IMR, num) = 1;
/* Enable the interrupt line */
enable_irq(num);
@@ -126,11 +126,11 @@ void exti_attach_interrupt(afio_exti_num num,
*/
void exti_detach_interrupt(afio_exti_num num) {
/* First, mask the interrupt request */
- *bb_perip(&EXTI_BASE->IMR, num) = 0;
+ *bb_peripv(&EXTI_BASE->IMR, num) = 0;
/* Then, clear the trigger selection registers */
- *bb_perip(&EXTI_BASE->FTSR, num) = 0;
- *bb_perip(&EXTI_BASE->RTSR, num) = 0;
+ *bb_peripv(&EXTI_BASE->FTSR, num) = 0;
+ *bb_peripv(&EXTI_BASE->RTSR, num) = 0;
/* Next, disable the IRQ, unless it's multiplexed and there are
* other active external interrupts on the same IRQ line */
@@ -210,7 +210,7 @@ void __irq_exti15_10(void) {
*/
static inline void clear_pending(uint32 exti_num) {
- *bb_perip(&EXTI_BASE->PR, exti_num) = 1;
+ *bb_peripv(&EXTI_BASE->PR, exti_num) = 1;
/* If the pending bit is cleared as the last instruction in an ISR,
* it won't actually be cleared in time and the ISR will fire again.
* Insert a 2-cycle buffer to allow it to take effect. */
diff --git a/libmaple/gpio.c b/libmaple/gpio.c
index 90be033..b08be12 100644
--- a/libmaple/gpio.c
+++ b/libmaple/gpio.c
@@ -61,7 +61,7 @@ static gpio_dev gpiod = {
/** GPIO port D device. */
gpio_dev *GPIOD = &gpiod;
-#ifdef STM32_HIGH_DENSITY
+#ifdef STM32_HIGH_
static gpio_dev gpioe = {
.regs = GPIOE_BASE,
.clk_id = RCC_GPIOE
diff --git a/libmaple/rcc.c b/libmaple/rcc.c
index e49382c..2841af3 100644
--- a/libmaple/rcc.c
+++ b/libmaple/rcc.c
@@ -23,115 +23,97 @@
*****************************************************************************/
/**
- * @file rcc.c
- * @brief Clock setup, peripheral enable and reset routines.
+ * @brief Implements pretty much only the basic clock setup on the
+ * stm32, clock enable/disable and peripheral reset commands.
*/
#include "libmaple.h"
#include "flash.h"
#include "rcc.h"
-#include "bitband.h"
-typedef enum clock_domain {
+enum {
APB1,
APB2,
AHB
-} clock_domain;
+};
struct rcc_dev_info {
- const clock_domain clk_domain;
+ const uint8 clk_domain;
const uint8 line_num;
};
/* device descriptor tables */
-static const __attr_flash struct rcc_dev_info rcc_dev_table[] = {
- [RCC_SRAM] = { .clk_domain = AHB, .line_num = 2 },
- [RCC_GPIOA] = { .clk_domain = APB2, .line_num = 2 },
- [RCC_GPIOB] = { .clk_domain = APB2, .line_num = 3 },
- [RCC_GPIOC] = { .clk_domain = APB2, .line_num = 4 },
- [RCC_GPIOD] = { .clk_domain = APB2, .line_num = 5 },
- [RCC_AFIO] = { .clk_domain = APB2, .line_num = 0 },
- [RCC_ADC1] = { .clk_domain = APB2, .line_num = 9 },
- [RCC_ADC2] = { .clk_domain = APB2, .line_num = 10 },
- [RCC_USART1] = { .clk_domain = APB2, .line_num = 14 },
- [RCC_USART2] = { .clk_domain = APB1, .line_num = 17 },
- [RCC_USART3] = { .clk_domain = APB1, .line_num = 18 },
- [RCC_TIMER1] = { .clk_domain = APB2, .line_num = 11 },
- [RCC_TIMER2] = { .clk_domain = APB1, .line_num = 0 },
- [RCC_TIMER3] = { .clk_domain = APB1, .line_num = 1 },
- [RCC_TIMER4] = { .clk_domain = APB1, .line_num = 2 },
- [RCC_SPI1] = { .clk_domain = APB2, .line_num = 12 },
- [RCC_SPI2] = { .clk_domain = APB1, .line_num = 14 },
- [RCC_DMA1] = { .clk_domain = AHB, .line_num = 0 },
- [RCC_PWR] = { .clk_domain = APB1, .line_num = 28 },
- [RCC_BKP] = { .clk_domain = APB1, .line_num = 27 },
- [RCC_CAN] = { .clk_domain = APB1, .line_num = 25 },
- [RCC_USB] = { .clk_domain = APB1, .line_num = 23 },
- [RCC_I2C1] = { .clk_domain = APB1, .line_num = 22 },
- [RCC_I2C2] = { .clk_domain = APB1, .line_num = 21 },
- [RCC_CRC] = { .clk_domain = AHB, .line_num = 6 },
- [RCC_WWDG] = { .clk_domain = APB2, .line_num = 11 },
- [RCC_FLITF] = { .clk_domain = AHB, .line_num = 4 },
-#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
- [RCC_SDIO] = { .clk_domain = AHB, .line_num = 10 },
- [RCC_FSMC] = { .clk_domain = AHB, .line_num = 8 },
- [RCC_GPIOE] = { .clk_domain = APB2, .line_num = 6 },
- [RCC_GPIOF] = { .clk_domain = APB2, .line_num = 7 },
- [RCC_GPIOG] = { .clk_domain = APB2, .line_num = 8 },
- [RCC_ADC3] = { .clk_domain = APB2, .line_num = 15 },
- [RCC_UART4] = { .clk_domain = APB1, .line_num = 19 },
- [RCC_UART5] = { .clk_domain = APB1, .line_num = 20 },
- [RCC_TIMER5] = { .clk_domain = APB1, .line_num = 3 },
- [RCC_TIMER6] = { .clk_domain = APB1, .line_num = 4 },
- [RCC_TIMER7] = { .clk_domain = APB1, .line_num = 5 },
- [RCC_TIMER8] = { .clk_domain = APB2, .line_num = 13 },
- [RCC_DAC] = { .clk_domain = APB1, .line_num = 29 },
- [RCC_DMA2] = { .clk_domain = AHB, .line_num = 1 },
- [RCC_SPI3] = { .clk_domain = APB1, .line_num = 15 },
-#endif
-#ifdef STM32_XL_DENSITY
- [RCC_TIMER9] = { .clk_domain = APB2, .line_num = 19 },
- [RCC_TIMER10] = { .clk_domain = APB2, .line_num = 20 },
- [RCC_TIMER11] = { .clk_domain = APB2, .line_num = 21 },
- [RCC_TIMER12] = { .clk_domain = APB1, .line_num = 6 },
- [RCC_TIMER13] = { .clk_domain = APB1, .line_num = 7 },
- [RCC_TIMER14] = { .clk_domain = APB1, .line_num = 8 },
-#endif
+static const struct rcc_dev_info rcc_dev_table[] = {
+ [RCC_GPIOA] = { .clk_domain = APB2, .line_num = 2 },
+ [RCC_GPIOB] = { .clk_domain = APB2, .line_num = 3 },
+ [RCC_GPIOC] = { .clk_domain = APB2, .line_num = 4 },
+ [RCC_GPIOD] = { .clk_domain = APB2, .line_num = 5 },
+ [RCC_GPIOE] = { .clk_domain = APB2, .line_num = 6 }, // High-density only
+ [RCC_GPIOF] = { .clk_domain = APB2, .line_num = 7 }, // High-density only
+ [RCC_GPIOG] = { .clk_domain = APB2, .line_num = 8 }, // High-density only
+ [RCC_AFIO] = { .clk_domain = APB2, .line_num = 0 },
+ [RCC_ADC1] = { .clk_domain = APB2, .line_num = 9 },
+ [RCC_ADC2] = { .clk_domain = APB2, .line_num = 10 },
+ [RCC_ADC3] = { .clk_domain = APB2, .line_num = 15 },
+ [RCC_USART1] = { .clk_domain = APB2, .line_num = 14 },
+ [RCC_USART2] = { .clk_domain = APB1, .line_num = 17 },
+ [RCC_USART3] = { .clk_domain = APB1, .line_num = 18 },
+ [RCC_UART4] = { .clk_domain = APB1, .line_num = 19 }, // High-density only
+ [RCC_UART5] = { .clk_domain = APB1, .line_num = 20 }, // High-density only
+ [RCC_TIMER1] = { .clk_domain = APB2, .line_num = 11 },
+ [RCC_TIMER2] = { .clk_domain = APB1, .line_num = 0 },
+ [RCC_TIMER3] = { .clk_domain = APB1, .line_num = 1 },
+ [RCC_TIMER4] = { .clk_domain = APB1, .line_num = 2 },
+ [RCC_TIMER5] = { .clk_domain = APB1, .line_num = 3 }, // High-density only
+ [RCC_TIMER6] = { .clk_domain = APB1, .line_num = 4 }, // High-density only
+ [RCC_TIMER7] = { .clk_domain = APB1, .line_num = 5 }, // High-density only
+ [RCC_TIMER8] = { .clk_domain = APB2, .line_num = 13 }, // High-density only
+ [RCC_SPI1] = { .clk_domain = APB2, .line_num = 12 },
+ [RCC_SPI2] = { .clk_domain = APB1, .line_num = 14 },
+ [RCC_FSMC] = { .clk_domain = AHB, .line_num = 8 }, // High-density only
+ [RCC_DAC] = { .clk_domain = APB1, .line_num = 29 }, // High-density only
+ [RCC_DMA1] = { .clk_domain = AHB, .line_num = 0 },
+ [RCC_DMA2] = { .clk_domain = AHB, .line_num = 1 }, // High-density only
+ [RCC_PWR] = { .clk_domain = APB1, .line_num = 28},
+ [RCC_BKP] = { .clk_domain = APB1, .line_num = 27}
};
/**
* @brief Initialize the clock control system. Initializes the system
* clock source to use the PLL driven by an external oscillator
* @param sysclk_src system clock source, must be PLL
- * @param pll_src pll clock source, must be RCC_CFGR_PLLSRC_HSE
+ * @param pll_src pll clock source, must be HSE
* @param pll_mul pll multiplier
*/
void rcc_clk_init(uint32 sysclk_src, uint32 pll_src, uint32 pll_mul) {
- uint32 cfgr;
-
/* Assume that we're going to clock the chip off the PLL, fed by
* the HSE */
ASSERT(sysclk_src == RCC_CLKSRC_PLL &&
- pll_src == RCC_CFGR_PLLSRC_HSE);
+ pll_src == RCC_PLLSRC_HSE);
+
+ uint32 cfgr = 0;
+ uint32 cr = RCC_READ_CR();
- RCC_BASE->CFGR = pll_src | pll_mul;
+ cfgr = (pll_src | pll_mul);
+ RCC_WRITE_CFGR(cfgr);
- /* Turn on the HSE */
- *bb_perip(&RCC_BASE->CR, RCC_CR_HSEON_BIT) = 1;
- while (!(*bb_perip(&RCC_BASE->CR, RCC_CR_HSERDY_BIT)))
+ /* Turn on the HSE */
+ cr |= RCC_CR_HSEON;
+ RCC_WRITE_CR(cr);
+ while (!(RCC_READ_CR() & RCC_CR_HSERDY))
;
- /* Now the PLL */
- *bb_perip(&RCC_BASE->CR, RCC_CR_PLLON_BIT) = 1;
- while (!(*bb_perip(&RCC_BASE->CR, RCC_CR_PLLRDY_BIT)))
+ /* Now the PLL */
+ cr |= RCC_CR_PLLON;
+ RCC_WRITE_CR(cr);
+ while (!(RCC_READ_CR() & RCC_CR_PLLRDY))
;
/* Finally, let's switch over to the PLL */
- cfgr = RCC_BASE->CFGR;
cfgr &= ~RCC_CFGR_SW;
cfgr |= RCC_CFGR_SW_PLL;
- RCC_BASE->CFGR = cfgr;
- while ((RCC_BASE->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL)
+ RCC_WRITE_CFGR(cfgr);
+ while ((RCC_READ_CFGR() & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL)
;
}
@@ -139,23 +121,16 @@ void rcc_clk_init(uint32 sysclk_src, uint32 pll_src, uint32 pll_mul) {
* @brief Turn on the clock line on a device
* @param device Clock ID of the device to turn on.
*/
-void rcc_clk_enable(rcc_clk_id id) {
- uint8 lnum = rcc_dev_table[id].line_num;
- __io uint32 *enr;
-
- switch(rcc_dev_table[id].clk_domain) {
- case APB1:
- enr = &RCC_BASE->APB1ENR;
- break;
- case APB2:
- enr = &RCC_BASE->APB2ENR;
- break;
- case AHB:
- enr = &RCC_BASE->AHBENR;
- break;
- }
-
- *bb_perip(enr, lnum) = 1;
+void rcc_clk_enable(rcc_clk_id device) {
+ static const uint32 enable_regs[] = {
+ [APB1] = RCC_APB1ENR,
+ [APB2] = RCC_APB2ENR,
+ [AHB] = RCC_AHBENR,
+ };
+
+ uint8 clk_domain = rcc_dev_table[device].clk_domain;
+
+ __set_bits(enable_regs[clk_domain], BIT(rcc_dev_table[device].line_num));
}
/**
@@ -163,7 +138,7 @@ void rcc_clk_enable(rcc_clk_id id) {
* @param prescaler prescaler to set
* @param divider prescaler divider
*/
-void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider) {
+void rcc_set_prescaler(uint32 prescaler, uint32 divider) {
static const uint32 masks[] = {
[RCC_PRESCALER_AHB] = RCC_CFGR_HPRE,
[RCC_PRESCALER_APB1] = RCC_CFGR_PPRE1,
@@ -171,39 +146,26 @@ void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider) {
[RCC_PRESCALER_USB] = RCC_CFGR_USBPRE,
[RCC_PRESCALER_ADC] = RCC_CFGR_ADCPRE,
};
- uint32 cfgr;
- cfgr = RCC_BASE->CFGR;
+ uint32 cfgr = RCC_READ_CFGR();
+
cfgr &= ~masks[prescaler];
cfgr |= divider;
- RCC_BASE->CFGR = cfgr;
+ RCC_WRITE_CFGR(cfgr);
}
/**
- * @brief Reset a device
- * @param device Clock ID of the device to reset; the device must be
- * on APB1 or APB2.
+ * @brief reset a device
+ * @param device Clock ID of the device to reset.
*/
-void rcc_reset_dev(rcc_clk_id id) {
- uint8 lnum = rcc_dev_table[id].line_num;
- __io uint32 *rstr = 0;
-
- switch (rcc_dev_table[id].clk_domain) {
- case APB1:
- rstr = &RCC_BASE->APB1RSTR;
- break;
- case APB2:
- rstr = &RCC_BASE->APB2RSTR;
- break;
- case AHB:
- ASSERT(0);
- break;
- }
-
- if (rstr == 0) {
- return;
- }
-
- *bb_perip(rstr, lnum) = 1;
- *bb_perip(rstr, lnum) = 0;
+void rcc_reset_dev(rcc_clk_id device) {
+ static const uint32 reset_regs[] = {
+ [APB1] = RCC_APB1RSTR,
+ [APB2] = RCC_APB2RSTR,
+ };
+
+ uint8 clk_domain = rcc_dev_table[device].clk_domain;
+
+ __set_bits(reset_regs[clk_domain], BIT(rcc_dev_table[device].line_num));
+ __clear_bits(reset_regs[clk_domain], BIT(rcc_dev_table[device].line_num));
}
diff --git a/libmaple/rcc.h b/libmaple/rcc.h
index 83b34ed..8697e01 100644
--- a/libmaple/rcc.h
+++ b/libmaple/rcc.h
@@ -24,7 +24,7 @@
/**
* @file rcc.h
- * @brief Reset and clock control (RCC) definitions and prototypes
+ * @brief reset and clock control definitions and prototypes
*/
#include "libmaple_types.h"
@@ -36,451 +36,78 @@
extern "C"{
#endif
-/** RCC register map type */
-typedef struct rcc_reg_map {
- __io uint32 CR; /**< Clock control register */
- __io uint32 CFGR; /**< Clock configuration register */
- __io uint32 CIR; /**< Clock interrupt register */
- __io uint32 APB2RSTR; /**< APB2 peripheral reset register */
- __io uint32 APB1RSTR; /**< APB1 peripheral reset register */
- __io uint32 AHBENR; /**< AHB peripheral clock enable register */
- __io uint32 APB2ENR; /**< APB2 peripheral clock enable register */
- __io uint32 APB1ENR; /**< APB1 peripheral clock enable register */
- __io uint32 BDCR; /**< Backup domain control register */
- __io uint32 CSR; /**< Control/status register */
-} rcc_reg_map;
-
-/*
- * RCC register map base address
- */
-
-#define RCC_BASE ((rcc_reg_map*)0x40021000)
-
-/*
- * RCC register bit definitions
- */
-
-/* Clock control register */
-
-#define RCC_CR_PLLRDY_BIT 25
-#define RCC_CR_PLLON_BIT 24
-#define RCC_CR_CSSON_BIT 19
-#define RCC_CR_HSEBYP_BIT 18
-#define RCC_CR_HSERDY_BIT 17
-#define RCC_CR_HSEON_BIT 16
-#define RCC_CR_HSIRDY_BIT 1
-#define RCC_CR_HSION_BIT 0
-
-#define RCC_CR_PLLRDY BIT(RCC_CR_PLLRDY_BIT)
-#define RCC_CR_PLLON BIT(RCC_CR_PLLON_BIT)
-#define RCC_CR_CSSON BIT(RCC_CR_CSSON_BIT)
-#define RCC_CR_HSEBYP BIT(RCC_CR_HSEBYP_BIT)
-#define RCC_CR_HSERDY BIT(RCC_CR_HSERDY_BIT)
-#define RCC_CR_HSEON BIT(RCC_CR_HSEON_BIT)
-#define RCC_CR_HSICAL (0xFF << 8)
-#define RCC_CR_HSITRIM (0x1F << 3)
-#define RCC_CR_HSIRDY BIT(RCC_CR_HSIRDY_BIT)
-#define RCC_CR_HSION BIT(RCC_CR_HSION_BIT)
-
-/* Clock configuration register */
-
-#define RCC_CFGR_USBPRE_BIT 22
-#define RCC_CFGR_PLLXTPRE_BIT 17
-#define RCC_CFGR_PLLSRC_BIT 16
-
-#define RCC_CFGR_MCO (0x7 << 24)
-#define RCC_CFGR_USBPRE BIT(RCC_CFGR_USBPRE_BIT)
-#define RCC_CFGR_PLLMUL (0xF << 18)
-#define RCC_CFGR_PLLMUL_2 (0x0 << 18)
-#define RCC_CFGR_PLLMUL_3 (0x1 << 18)
-#define RCC_CFGR_PLLMUL_4 (0x2 << 18)
-#define RCC_CFGR_PLLMUL_5 (0x3 << 18)
-#define RCC_CFGR_PLLMUL_6 (0x4 << 18)
-#define RCC_CFGR_PLLMUL_7 (0x5 << 18)
-#define RCC_CFGR_PLLMUL_8 (0x6 << 18)
-#define RCC_CFGR_PLLMUL_9 (0x7 << 18)
-#define RCC_CFGR_PLLMUL_10 (0x8 << 18)
-#define RCC_CFGR_PLLMUL_11 (0x9 << 18)
-#define RCC_CFGR_PLLMUL_12 (0xA << 18)
-#define RCC_CFGR_PLLMUL_13 (0xB << 18)
-#define RCC_CFGR_PLLMUL_14 (0xC << 18)
-#define RCC_CFGR_PLLMUL_15 (0xD << 18)
-#define RCC_CFGR_PLLMUL_16 (0xE << 18)
-#define RCC_CFGR_PLLXTPRE BIT(RCC_CFGR_PLLXTPRE_BIT)
-#define RCC_CFGR_PLLSRC BIT(RCC_CFGR_PLLSRC_BIT)
-#define RCC_CFGR_PLLSRC_HSI_DIV_2 (0 << RCC_CFGR_PLLSRC_BIT)
-#define RCC_CFGR_PLLSRC_HSE (1 << RCC_CFGR_PLLSRC_BIT)
-#define RCC_CFGR_ADCPRE (0x3 << 14)
-#define RCC_CFGR_PPRE2 (0x7 << 11)
-#define RCC_CFGR_PPRE1 (0x7 << 8)
-#define RCC_CFGR_HPRE (0xF << 4)
-#define RCC_CFGR_SWS (0x3 << 2)
-#define RCC_CFGR_SWS_PLL (0x2 << 2)
-#define RCC_CFGR_SWS_HSE (0x1 << 2)
-#define RCC_CFGR_SW (0x3 << 0)
-#define RCC_CFGR_SW_PLL (0x2 << 0)
-#define RCC_CFGR_SW_HSE (0x1 << 0)
-
-/* Clock interrupt register */
-
-#define RCC_CIR_CSSC_BIT 23
-#define RCC_CIR_PLLRDYC_BIT 20
-#define RCC_CIR_HSERDYC_BIT 19
-#define RCC_CIR_HSIRDYC_BIT 18
-#define RCC_CIR_LSERDYC_BIT 17
-#define RCC_CIR_LSIRDYC_BIT 16
-#define RCC_CIR_PLLRDYIE_BIT 12
-#define RCC_CIR_HSERDYIE_BIT 11
-#define RCC_CIR_HSIRDYIE_BIT 10
-#define RCC_CIR_LSERDYIE_BIT 9
-#define RCC_CIR_LSIRDYIE_BIT 8
-#define RCC_CIR_CSSF_BIT 7
-#define RCC_CIR_PLLRDYF_BIT 4
-#define RCC_CIR_HSERDYF_BIT 3
-#define RCC_CIR_HSIRDYF_BIT 2
-#define RCC_CIR_LSERDYF_BIT 1
-#define RCC_CIR_LSIRDYF_BIT 0
-
-#define RCC_CIR_CSSC BIT(RCC_CIR_CSSC_BIT)
-#define RCC_CIR_PLLRDYC BIT(RCC_CIR_PLLRDYC_BIT)
-#define RCC_CIR_HSERDYC BIT(RCC_CIR_HSERDYC_BIT)
-#define RCC_CIR_HSIRDYC BIT(RCC_CIR_HSIRDYC_BIT)
-#define RCC_CIR_LSERDYC BIT(RCC_CIR_LSERDYC_BIT)
-#define RCC_CIR_LSIRDYC BIT(RCC_CIR_LSIRDYC_BIT)
-#define RCC_CIR_PLLRDYIE BIT(RCC_CIR_PLLRDYIE_BIT)
-#define RCC_CIR_HSERDYIE BIT(RCC_CIR_HSERDYIE_BIT)
-#define RCC_CIR_HSIRDYIE BIT(RCC_CIR_HSIRDYIE_BIT)
-#define RCC_CIR_LSERDYIE BIT(RCC_CIR_LSERDYIE_BIT)
-#define RCC_CIR_LSIRDYIE BIT(RCC_CIR_LSIRDYIE_BIT)
-#define RCC_CIR_CSSF BIT(RCC_CIR_CSSF_BIT)
-#define RCC_CIR_PLLRDYF BIT(RCC_CIR_PLLRDYF_BIT)
-#define RCC_CIR_HSERDYF BIT(RCC_CIR_HSERDYF_BIT)
-#define RCC_CIR_HSIRDYF BIT(RCC_CIR_HSIRDYF_BIT)
-#define RCC_CIR_LSERDYF BIT(RCC_CIR_LSERDYF_BIT)
-#define RCC_CIR_LSIRDYF BIT(RCC_CIR_LSIRDYF_BIT)
-
-/* APB2 peripheral reset register */
-
-#define RCC_APB2RSTR_TIM11RST_BIT 21
-#define RCC_APB2RSTR_TIM10RST_BIT 20
-#define RCC_APB2RSTR_TIM9RST_BIT 19
-#define RCC_APB2RSTR_ADC3RST_BIT 15
-#define RCC_APB2RSTR_USART1RST_BIT 14
-#define RCC_APB2RSTR_TIM8RST_BIT 13
-#define RCC_APB2RSTR_SPI1RST_BIT 12
-#define RCC_APB2RSTR_TIM1RST_BIT 11
-#define RCC_APB2RSTR_ADC2RST_BIT 10
-#define RCC_APB2RSTR_ADC1RST_BIT 9
-#define RCC_APB2RSTR_IOPGRST_BIT 8
-#define RCC_APB2RSTR_IOPFRST_BIT 7
-#define RCC_APB2RSTR_IOPERST_BIT 6
-#define RCC_APB2RSTR_IOPDRST_BIT 5
-#define RCC_APB2RSTR_IOPCRST_BIT 4
-#define RCC_APB2RSTR_IOPBRST_BIT 3
-#define RCC_APB2RSTR_IOPARST_BIT 2
-#define RCC_APB2RSTR_AFIORST_BIT 0
-
-#define RCC_APB2RSTR_TIM11RST BIT(RCC_APB2RSTR_TIM11RST_BIT)
-#define RCC_APB2RSTR_TIM10RST BIT(RCC_APB2RSTR_TIM10RST_BIT)
-#define RCC_APB2RSTR_TIM9RST BIT(RCC_APB2RSTR_TIM9RST_BIT)
-#define RCC_APB2RSTR_ADC3RST BIT(RCC_APB2RSTR_ADC3RST_BIT)
-#define RCC_APB2RSTR_USART1RST BIT(RCC_APB2RSTR_USART1RST_BIT)
-#define RCC_APB2RSTR_TIM8RST BIT(RCC_APB2RSTR_TIM8RST_BIT)
-#define RCC_APB2RSTR_SPI1RST BIT(RCC_APB2RSTR_SPI1RST_BIT)
-#define RCC_APB2RSTR_TIM1RST BIT(RCC_APB2RSTR_TIM1RST_BIT)
-#define RCC_APB2RSTR_ADC2RST BIT(RCC_APB2RSTR_ADC2RST_BIT)
-#define RCC_APB2RSTR_ADC1RST BIT(RCC_APB2RSTR_ADC1RST_BIT)
-#define RCC_APB2RSTR_IOPGRST BIT(RCC_APB2RSTR_IOPGRST_BIT)
-#define RCC_APB2RSTR_IOPFRST BIT(RCC_APB2RSTR_IOPFRST_BIT)
-#define RCC_APB2RSTR_IOPERST BIT(RCC_APB2RSTR_IOPERST_BIT)
-#define RCC_APB2RSTR_IOPDRST BIT(RCC_APB2RSTR_IOPDRST_BIT)
-#define RCC_APB2RSTR_IOPCRST BIT(RCC_APB2RSTR_IOPCRST_BIT)
-#define RCC_APB2RSTR_IOPBRST BIT(RCC_APB2RSTR_IOPBRST_BIT)
-#define RCC_APB2RSTR_IOPARST BIT(RCC_APB2RSTR_IOPARST_BIT)
-#define RCC_APB2RSTR_AFIORST BIT(RCC_APB2RSTR_AFIORST_BIT)
-
-/* APB1 peripheral reset register */
-
-#define RCC_APB1RSTR_DACRST_BIT 29
-#define RCC_APB1RSTR_PWRRST_BIT 28
-#define RCC_APB1RSTR_BKPRST_BIT 27
-#define RCC_APB1RSTR_CANRST_BIT 25
-#define RCC_APB1RSTR_USBRST_BIT 23
-#define RCC_APB1RSTR_I2C2RST_BIT 22
-#define RCC_APB1RSTR_I2C1RST_BIT 21
-#define RCC_APB1RSTR_UART5RST_BIT 20
-#define RCC_APB1RSTR_UART4RST_BIT 19
-#define RCC_APB1RSTR_UART3RST_BIT 18
-#define RCC_APB1RSTR_UART2RST_BIT 17
-#define RCC_APB1RSTR_SPI3RST_BIT 15
-#define RCC_APB1RSTR_SPI2RST_BIT 14
-#define RCC_APB1RSTR_WWDGRST_BIT 11
-#define RCC_APB1RSTR_TIM14RST_BIT 8
-#define RCC_APB1RSTR_TIM13RST_BIT 7
-#define RCC_APB1RSTR_TIM12RST_BIT 6
-#define RCC_APB1RSTR_TIM7RST_BIT 5
-#define RCC_APB1RSTR_TIM6RST_BIT 4
-#define RCC_APB1RSTR_TIM5RST_BIT 3
-#define RCC_APB1RSTR_TIM4RST_BIT 2
-#define RCC_APB1RSTR_TIM3RST_BIT 1
-#define RCC_APB1RSTR_TIM2RST_BIT 0
-
-#define RCC_APB1RSTR_DACRST BIT(RCC_APB1RSTR_DACRST_BIT)
-#define RCC_APB1RSTR_PWRRST BIT(RCC_APB1RSTR_PWRRST_BIT)
-#define RCC_APB1RSTR_BKPRST BIT(RCC_APB1RSTR_BKPRST_BIT)
-#define RCC_APB1RSTR_CANRST BIT(RCC_APB1RSTR_CANRST_BIT)
-#define RCC_APB1RSTR_USBRST BIT(RCC_APB1RSTR_USBRST_BIT)
-#define RCC_APB1RSTR_I2C2RST BIT(RCC_APB1RSTR_I2C2RST_BIT)
-#define RCC_APB1RSTR_I2C1RST BIT(RCC_APB1RSTR_I2C1RST_BIT)
-#define RCC_APB1RSTR_UART5RST BIT(RCC_APB1RSTR_UART5RST_BIT)
-#define RCC_APB1RSTR_UART4RST BIT(RCC_APB1RSTR_UART4RST_BIT)
-#define RCC_APB1RSTR_UART3RST BIT(RCC_APB1RSTR_UART3RST_BIT)
-#define RCC_APB1RSTR_UART2RST BIT(RCC_APB1RSTR_UART2RST_BIT)
-#define RCC_APB1RSTR_SPI3RST BIT(RCC_APB1RSTR_SPI3RST_BIT)
-#define RCC_APB1RSTR_SPI2RST BIT(RCC_APB1RSTR_SPI2RST_BIT)
-#define RCC_APB1RSTR_WWDGRST BIT(RCC_APB1RSTR_WWDGRST_BIT)
-#define RCC_APB1RSTR_TIM14RST BIT(RCC_APB1RSTR_TIM14RST_BIT)
-#define RCC_APB1RSTR_TIM13RST BIT(RCC_APB1RSTR_TIM13RST_BIT)
-#define RCC_APB1RSTR_TIM12RST BIT(RCC_APB1RSTR_TIM12RST_BIT)
-#define RCC_APB1RSTR_TIM7RST BIT(RCC_APB1RSTR_TIM7RST_BIT)
-#define RCC_APB1RSTR_TIM6RST BIT(RCC_APB1RSTR_TIM6RST_BIT)
-#define RCC_APB1RSTR_TIM5RST BIT(RCC_APB1RSTR_TIM5RST_BIT)
-#define RCC_APB1RSTR_TIM4RST BIT(RCC_APB1RSTR_TIM4RST_BIT)
-#define RCC_APB1RSTR_TIM3RST BIT(RCC_APB1RSTR_TIM3RST_BIT)
-#define RCC_APB1RSTR_TIM2RST BIT(RCC_APB1RSTR_TIM2RST_BIT)
-
-/* AHB peripheral clock enable register */
-
-#define RCC_AHBENR_SDIOEN_BIT 10
-#define RCC_AHBENR_FSMCEN_BIT 8
-#define RCC_AHBENR_CRCEN_BIT 6
-#define RCC_AHBENR_FLITFEN_BIT 4
-#define RCC_AHBENR_SRAMEN_BIT 2
-#define RCC_AHBENR_DMA2EN_BIT 1
-#define RCC_AHBENR_DMA1EN_BIT 0
-
-#define RCC_AHBENR_SDIOEN BIT(RCC_AHBENR_SDIOEN_BIT)
-#define RCC_AHBENR_FSMCEN BIT(RCC_AHBENR_FSMCEN_BIT)
-#define RCC_AHBENR_CRCEN BIT(RCC_AHBENR_CRCEN_BIT)
-#define RCC_AHBENR_FLITFEN BIT(RCC_AHBENR_FLITFEN_BIT)
-#define RCC_AHBENR_SRAMEN BIT(RCC_AHBENR_SRAMEN_BIT)
-#define RCC_AHBENR_DMA2EN BIT(RCC_AHBENR_DMA2EN_BIT)
-#define RCC_AHBENR_DMA1EN BIT(RCC_AHBENR_DMA1EN_BIT)
-
-/* APB2 peripheral clock enable register */
-
-#define RCC_APB2ENR_TIM11EN_BIT 21
-#define RCC_APB2ENR_TIM10EN_BIT 20
-#define RCC_APB2ENR_TIM9EN_BIT 19
-#define RCC_APB2ENR_ADC3EN_BIT 15
-#define RCC_APB2ENR_USART1EN_BIT 14
-#define RCC_APB2ENR_TIM8EN_BIT 13
-#define RCC_APB2ENR_SPI1EN_BIT 12
-#define RCC_APB2ENR_TIM1EN_BIT 11
-#define RCC_APB2ENR_ADC2EN_BIT 10
-#define RCC_APB2ENR_ADC1EN_BIT 9
-#define RCC_APB2ENR_IOPGEN_BIT 8
-#define RCC_APB2ENR_IOPFEN_BIT 7
-#define RCC_APB2ENR_IOPEEN_BIT 6
-#define RCC_APB2ENR_IOPDEN_BIT 5
-#define RCC_APB2ENR_IOPCEN_BIT 4
-#define RCC_APB2ENR_IOPBEN_BIT 3
-#define RCC_APB2ENR_IOPAEN_BIT 2
-#define RCC_APB2ENR_AFIOEN_BIT 0
-
-#define RCC_APB2ENR_TIM11EN BIT(RCC_APB2ENR_TIM11EN_BIT)
-#define RCC_APB2ENR_TIM10EN BIT(RCC_APB2ENR_TIM10EN_BIT)
-#define RCC_APB2ENR_TIM9EN BIT(RCC_APB2ENR_TIM9EN_BIT)
-#define RCC_APB2ENR_ADC3EN BIT(RCC_APB2ENR_ADC3EN_BIT)
-#define RCC_APB2ENR_USART1EN BIT(RCC_APB2ENR_USART1EN_BIT)
-#define RCC_APB2ENR_TIM8EN BIT(RCC_APB2ENR_TIM8EN_BIT)
-#define RCC_APB2ENR_SPI1EN BIT(RCC_APB2ENR_SPI1EN_BIT)
-#define RCC_APB2ENR_TIM1EN BIT(RCC_APB2ENR_TIM1EN_BIT)
-#define RCC_APB2ENR_ADC2EN BIT(RCC_APB2ENR_ADC2EN_BIT)
-#define RCC_APB2ENR_ADC1EN BIT(RCC_APB2ENR_ADC1EN_BIT)
-#define RCC_APB2ENR_IOPGEN BIT(RCC_APB2ENR_IOPGEN_BIT)
-#define RCC_APB2ENR_IOPFEN BIT(RCC_APB2ENR_IOPFEN_BIT)
-#define RCC_APB2ENR_IOPEEN BIT(RCC_APB2ENR_IOPEEN_BIT)
-#define RCC_APB2ENR_IOPDEN BIT(RCC_APB2ENR_IOPDEN_BIT)
-#define RCC_APB2ENR_IOPCEN BIT(RCC_APB2ENR_IOPCEN_BIT)
-#define RCC_APB2ENR_IOPBEN BIT(RCC_APB2ENR_IOPBEN_BIT)
-#define RCC_APB2ENR_IOPAEN BIT(RCC_APB2ENR_IOPAEN_BIT)
-#define RCC_APB2ENR_AFIOEN BIT(RCC_APB2ENR_AFIOEN_BIT)
-
-/* APB1 peripheral clock enable register */
-
-#define RCC_APB1ENR_DACEN_BIT 29
-#define RCC_APB1ENR_BKPEN_BIT 27
-#define RCC_APB1ENR_PWREN_BIT 28
-#define RCC_APB1ENR_CANEN_BIT 25
-#define RCC_APB1ENR_USBEN_BIT 23
-#define RCC_APB1ENR_I2C2EN_BIT 22
-#define RCC_APB1ENR_I2C1EN_BIT 21
-#define RCC_APB1ENR_UART5EN_BIT 20
-#define RCC_APB1ENR_UART4EN_BIT 19
-#define RCC_APB1ENR_UART3EN_BIT 18
-#define RCC_APB1ENR_UART2EN_BIT 17
-#define RCC_APB1ENR_SPI3EN_BIT 15
-#define RCC_APB1ENR_SPI2EN_BIT 14
-#define RCC_APB1ENR_WWDGEN_BIT 11
-#define RCC_APB1ENR_TIM14EN_BIT 8
-#define RCC_APB1ENR_TIM13EN_BIT 7
-#define RCC_APB1ENR_TIM12EN_BIT 6
-#define RCC_APB1ENR_TIM7EN_BIT 5
-#define RCC_APB1ENR_TIM6EN_BIT 4
-#define RCC_APB1ENR_TIM5EN_BIT 3
-#define RCC_APB1ENR_TIM4EN_BIT 2
-#define RCC_APB1ENR_TIM3EN_BIT 1
-#define RCC_APB1ENR_TIM2EN_BIT 0
-
-#define RCC_APB1ENR_DACEN BIT(RCC_APB1ENR_DACEN_BIT)
-#define RCC_APB1ENR_PWREN BIT(RCC_APB1ENR_PWREN_BIT)
-#define RCC_APB1ENR_BKPEN BIT(RCC_APB1ENR_BKPEN_BIT)
-#define RCC_APB1ENR_CANEN BIT(RCC_APB1ENR_CANEN_BIT)
-#define RCC_APB1ENR_USBEN BIT(RCC_APB1ENR_USBEN_BIT)
-#define RCC_APB1ENR_I2C2EN BIT(RCC_APB1ENR_I2C2EN_BIT)
-#define RCC_APB1ENR_I2C1EN BIT(RCC_APB1ENR_I2C1EN_BIT)
-#define RCC_APB1ENR_UART5EN BIT(RCC_APB1ENR_UART5EN_BIT)
-#define RCC_APB1ENR_UART4EN BIT(RCC_APB1ENR_UART4EN_BIT)
-#define RCC_APB1ENR_UART3EN BIT(RCC_APB1ENR_UART3EN_BIT)
-#define RCC_APB1ENR_UART2EN BIT(RCC_APB1ENR_UART2EN_BIT)
-#define RCC_APB1ENR_SPI3EN BIT(RCC_APB1ENR_SPI3EN_BIT)
-#define RCC_APB1ENR_SPI2EN BIT(RCC_APB1ENR_SPI2EN_BIT)
-#define RCC_APB1ENR_WWDGEN BIT(RCC_APB1ENR_WWDGEN_BIT)
-#define RCC_APB1ENR_TIM14EN BIT(RCC_APB1ENR_TIM14EN_BIT)
-#define RCC_APB1ENR_TIM13EN BIT(RCC_APB1ENR_TIM13EN_BIT)
-#define RCC_APB1ENR_TIM12EN BIT(RCC_APB1ENR_TIM12EN_BIT)
-#define RCC_APB1ENR_TIM7EN BIT(RCC_APB1ENR_TIM7EN_BIT)
-#define RCC_APB1ENR_TIM6EN BIT(RCC_APB1ENR_TIM6EN_BIT)
-#define RCC_APB1ENR_TIM5EN BIT(RCC_APB1ENR_TIM5EN_BIT)
-#define RCC_APB1ENR_TIM4EN BIT(RCC_APB1ENR_TIM4EN_BIT)
-#define RCC_APB1ENR_TIM3EN BIT(RCC_APB1ENR_TIM3EN_BIT)
-#define RCC_APB1ENR_TIM2EN BIT(RCC_APB1ENR_TIM2EN_BIT)
-
-/* Backup domain control register */
-
-#define RCC_BDCR_BDRST_BIT 16
-#define RCC_BDCR_RTCEN_BIT 15
-#define RCC_BDCR_LSEBYP_BIT 2
-#define RCC_BDCR_LSERDY_BIT 1
-#define RCC_BDCR_LSEON_BIT 0
-
-#define RCC_BDCR_BDRST BIT(RCC_BDCR_BDRST_BIT)
-#define RCC_BDCR_RTCEN BIT(RCC_BDCR_RTCEN_BIT)
-#define RCC_BDCR_RTCSEL (0x3 << 8)
-#define RCC_BDCR_RTCSEL_LSE (0x1 << 8)
-#define RCC_BDCR_RTCSEL_LSI (0x2 << 8)
-#define RCC_BDCR_RTCSEL_HSE_DIV_128 (0x3 << 8)
-#define RCC_BDCR_LSEBYP BIT(RCC_BDCR_LSEBYP_BIT)
-#define RCC_BDCR_LSERDY BIT(RCC_BDCR_LSERDY_BIT)
-#define RCC_BDCR_LSEON BIT(RCC_BDCR_LSEON_BIT)
-
-/* Control/status register */
-
-#define RCC_CSR_LPWRRSTF_BIT 31
-#define RCC_CSR_WWDGRSTF_BIT 30
-#define RCC_CSR_IWDGRSTF_BIT 29
-#define RCC_CSR_SFTRSTF_BIT 28
-#define RCC_CSR_PORRSTF_BIT 27
-#define RCC_CSR_PINRSTF_BIT 26
-#define RCC_CSR_RMVF_BIT 25
-#define RCC_CSR_LSIRDY_BIT 1
-#define RCC_CSR_LSION_BIT 0
-
-#define RCC_CSR_LPWRRSTF BIT(RCC_CSR_LPWRRSTF_BIT)
-#define RCC_CSR_WWDGRSTF BIT(RCC_CSR_WWDGRSTF_BIT)
-#define RCC_CSR_IWDGRSTF BIT(RCC_CSR_IWDGRSTF_BIT)
-#define RCC_CSR_SFTRSTF BIT(RCC_CSR_SFTRSTF_BIT)
-#define RCC_CSR_PORRSTF BIT(RCC_CSR_PORRSTF_BIT)
-#define RCC_CSR_PINRSTF BIT(RCC_CSR_PINRSTF_BIT)
-#define RCC_CSR_RMVF BIT(RCC_CSR_RMVF_BIT)
-#define RCC_CSR_LSIRDY BIT(RCC_CSR_LSIRDY_BIT)
-#define RCC_CSR_LSION BIT(RCC_CSR_LSION_BIT)
-
-/**
- * Identifies bus and clock line for a device
- */
-typedef enum {
- RCC_SRAM,
- RCC_GPIOA,
- RCC_GPIOB,
- RCC_GPIOC,
- RCC_GPIOD,
- RCC_AFIO,
- RCC_ADC1,
- RCC_ADC2,
- RCC_USART1,
- RCC_USART2,
- RCC_USART3,
- RCC_TIMER1,
- RCC_TIMER2,
- RCC_TIMER3,
- RCC_TIMER4,
- RCC_SPI1,
- RCC_SPI2,
- RCC_DMA1,
- RCC_PWR,
- RCC_BKP,
- RCC_CAN,
- RCC_USB,
- RCC_I2C1,
- RCC_I2C2,
- RCC_CRC,
- RCC_WWDG,
- RCC_FLITF,
-#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
- RCC_SDIO,
- RCC_FSMC,
- RCC_GPIOE,
- RCC_GPIOF,
- RCC_GPIOG,
- RCC_ADC3,
- RCC_UART4,
- RCC_UART5,
- RCC_TIMER5,
- RCC_TIMER6,
- RCC_TIMER7,
- RCC_TIMER8,
- RCC_DAC,
- RCC_DMA2,
- RCC_SPI3,
-#endif
-#ifdef STM32_XL_DENSITY
- RCC_TIMER9,
- RCC_TIMER10,
- RCC_TIMER11,
- RCC_TIMER12,
- RCC_TIMER13,
- RCC_TIMER14,
-#endif
-} rcc_clk_id;
-
-/* SYSCLK source */
+/* registers */
+#define RCC_BASE 0x40021000
+#define RCC_CR (RCC_BASE + 0x0)
+#define RCC_CFGR (RCC_BASE + 0x4)
+#define RCC_CIR (RCC_BASE + 0x8)
+#define RCC_APB2RSTR (RCC_BASE + 0xC)
+#define RCC_APB1RSTR (RCC_BASE + 0x10)
+#define RCC_AHBENR (RCC_BASE + 0x14)
+#define RCC_APB2ENR (RCC_BASE + 0x18)
+#define RCC_APB1ENR (RCC_BASE + 0x1C)
+#define RCC_BDCR (RCC_BASE + 0x20)
+#define RCC_CSR (RCC_BASE + 0x24)
+#define RCC_AHBSTR (RCC_BASE + 0x28)
+#define RCC_CFGR2 (RCC_BASE + 0x2C)
+
+#define RCC_CFGR_USBPRE (0x1 << 22)
+#define RCC_CFGR_ADCPRE (0x3 << 14)
+#define RCC_CFGR_PPRE1 (0x7 << 8)
+#define RCC_CFGR_PPRE2 (0x7 << 11)
+#define RCC_CFGR_HPRE (0xF << 4)
+#define RCC_CFGR_PLLSRC (0x1 << 16)
+
+#define RCC_CFGR_SWS (0x3 << 2)
+#define RCC_CFGR_SWS_PLL (0x2 << 2)
+#define RCC_CFGR_SWS_HSE (0x1 << 2)
+
+#define RCC_CFGR_SW (0x3 << 0)
+#define RCC_CFGR_SW_PLL (0x2 << 0)
+#define RCC_CFGR_SW_HSE (0x1 << 0)
+
+/* CR status bits */
+#define RCC_CR_HSEON (0x1 << 16)
+#define RCC_CR_HSERDY (0x1 << 17)
+#define RCC_CR_PLLON (0x1 << 24)
+#define RCC_CR_PLLRDY (0x1 << 25)
+
+#define RCC_WRITE_CFGR(val) __write(RCC_CFGR, val)
+#define RCC_READ_CFGR() __read(RCC_CFGR)
+
+#define RCC_WRITE_CR(val) __write(RCC_CR, val)
+#define RCC_READ_CR() __read(RCC_CR)
+
+/* sysclk source */
#define RCC_CLKSRC_HSI (0x0)
#define RCC_CLKSRC_HSE (0x1)
#define RCC_CLKSRC_PLL (0x2)
-/* ADC prescaler dividers */
+/* pll entry clock source */
+#define RCC_PLLSRC_HSE (0x1 << 16)
+#define RCC_PLLSRC_HSI_DIV_2 (0x0 << 16)
+
+/* adc prescaler dividers */
#define RCC_ADCPRE_PCLK_DIV_2 (0x0 << 14)
#define RCC_ADCPRE_PCLK_DIV_4 (0x1 << 14)
#define RCC_ADCPRE_PCLK_DIV_6 (0x2 << 14)
#define RCC_ADCPRE_PCLK_DIV_8 (0x3 << 14)
-/* APB1 prescaler dividers */
+/* apb1 prescaler dividers */
#define RCC_APB1_HCLK_DIV_1 (0x0 << 8)
#define RCC_APB1_HCLK_DIV_2 (0x4 << 8)
#define RCC_APB1_HCLK_DIV_4 (0x5 << 8)
#define RCC_APB1_HCLK_DIV_8 (0x6 << 8)
#define RCC_APB1_HCLK_DIV_16 (0x7 << 8)
-/* APB2 prescaler dividers */
+/* apb2 prescaler dividers */
#define RCC_APB2_HCLK_DIV_1 (0x0 << 11)
#define RCC_APB2_HCLK_DIV_2 (0x4 << 11)
#define RCC_APB2_HCLK_DIV_4 (0x5 << 11)
#define RCC_APB2_HCLK_DIV_8 (0x6 << 11)
#define RCC_APB2_HCLK_DIV_16 (0x7 << 11)
-/* AHB prescaler dividers */
+/* ahb prescaler dividers */
#define RCC_AHB_SYSCLK_DIV_1 (0x0 << 4)
#define RCC_AHB_SYSCLK_DIV_2 (0x8 << 4)
#define RCC_AHB_SYSCLK_DIV_4 (0x9 << 4)
@@ -492,19 +119,75 @@ typedef enum {
#define RCC_AHB_SYSCLK_DIV_256 (0xE << 4)
#define RCC_AHB_SYSCLK_DIV_512 (0xF << 4)
-/* Prescalers */
-typedef enum rcc_prescaler {
+/* pll multipliers */
+#define RCC_PLLMUL_2 (0x0 << 18)
+#define RCC_PLLMUL_3 (0x1 << 18)
+#define RCC_PLLMUL_4 (0x2 << 18)
+#define RCC_PLLMUL_5 (0x3 << 18)
+#define RCC_PLLMUL_6 (0x4 << 18)
+#define RCC_PLLMUL_7 (0x5 << 18)
+#define RCC_PLLMUL_8 (0x6 << 18)
+#define RCC_PLLMUL_9 (0x7 << 18)
+#define RCC_PLLMUL_10 (0x8 << 18)
+#define RCC_PLLMUL_11 (0x9 << 18)
+#define RCC_PLLMUL_12 (0xA << 18)
+#define RCC_PLLMUL_13 (0xB << 18)
+#define RCC_PLLMUL_14 (0xC << 18)
+#define RCC_PLLMUL_15 (0xD << 18)
+#define RCC_PLLMUL_16 (0xE << 18)
+
+
+/* prescalers */
+enum {
RCC_PRESCALER_AHB,
RCC_PRESCALER_APB1,
RCC_PRESCALER_APB2,
RCC_PRESCALER_USB,
RCC_PRESCALER_ADC
-} rcc_prescaler;
+};
+
+/*
+ * Identifies bus and clock line for a device
+ */
+typedef enum {
+ RCC_GPIOA,
+ RCC_GPIOB,
+ RCC_GPIOC,
+ RCC_GPIOD,
+ RCC_GPIOE, // High-density devices only (Maple Native)
+ RCC_GPIOF, // High-density devices only (Maple Native)
+ RCC_GPIOG, // High-density devices only (Maple Native)
+ RCC_AFIO,
+ RCC_ADC1,
+ RCC_ADC2,
+ RCC_ADC3,
+ RCC_USART1,
+ RCC_USART2,
+ RCC_USART3,
+ RCC_UART4, // High-density devices only (Maple Native)
+ RCC_UART5, // High-density devices only (Maple Native)
+ RCC_TIMER1,
+ RCC_TIMER2,
+ RCC_TIMER3,
+ RCC_TIMER4,
+ RCC_TIMER5, // High-density devices only (Maple Native)
+ RCC_TIMER6, // High-density devices only (Maple Native)
+ RCC_TIMER7, // High-density devices only (Maple Native)
+ RCC_TIMER8, // High-density devices only (Maple Native)
+ RCC_SPI1,
+ RCC_SPI2,
+ RCC_FSMC, // High-density devices only (Maple Native)
+ RCC_DAC, // High-density devices only (Maple Native)
+ RCC_DMA1,
+ RCC_DMA2, // High-density devices only (Maple Native)
+ RCC_PWR,
+ RCC_BKP,
+} rcc_clk_id;
void rcc_clk_init(uint32 sysclk_src, uint32 pll_src, uint32 pll_mul);
void rcc_clk_enable(rcc_clk_id device);
void rcc_reset_dev(rcc_clk_id device);
-void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider);
+void rcc_set_prescaler(uint32 prescaler, uint32 divider);
#ifdef __cplusplus
} // extern "C"
diff --git a/wirish/boards.cpp b/wirish/boards.cpp
index 66f008f..1256ba1 100644
--- a/wirish/boards.cpp
+++ b/wirish/boards.cpp
@@ -304,7 +304,7 @@ PinMapping PIN_MAP[NR_GPIO_PINS] = {
/* D98/PG5 */
{GPIOG, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
/* D99/PD10 */
- {GPIOD, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD}
+ {GPIOD, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PDD}
};
#elif defined(BOARD_maple_mini)
diff --git a/wirish/wirish.cpp b/wirish/wirish.cpp
index c5a9e30..65d0262 100644
--- a/wirish/wirish.cpp
+++ b/wirish/wirish.cpp
@@ -53,7 +53,7 @@ void init(void) {
#endif
/* initialize clocks */
- rcc_clk_init(RCC_CLKSRC_PLL, RCC_CFGR_PLLSRC_HSE, RCC_CFGR_PLLMUL_9);
+ rcc_clk_init(RCC_CLKSRC_PLL, RCC_PLLSRC_HSE, RCC_PLLMUL_9);
rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1);
rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2);
rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1);