aboutsummaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
-rw-r--r--Makefile4
-rw-r--r--core/wiring.c66
-rw-r--r--libmaple/adc.c17
-rw-r--r--libmaple/gpio.c14
-rw-r--r--libmaple/rcc.c113
-rw-r--r--libmaple/rcc.h107
-rw-r--r--libmaple/timers.c10
-rw-r--r--libmaple/usart.c10
-rw-r--r--libmaple/util.h6
-rw-r--r--stm32lib/inc/stm32f10x_map.h2
10 files changed, 255 insertions, 94 deletions
diff --git a/Makefile b/Makefile
index 2d17532..bdc2bf1 100644
--- a/Makefile
+++ b/Makefile
@@ -62,8 +62,7 @@ ODFLAGS = -S
MAIN=main.c
STM32SRCS = $(STM_SRC)/stm32f10x_flash.c \
- $(STM_SRC)/stm32f10x_nvic.c \
- $(STM_SRC)/stm32f10x_rcc.c
+ $(STM_SRC)/stm32f10x_nvic.c
CSRC = libmaple/systick.c \
libmaple/timers.c \
@@ -76,6 +75,7 @@ CSRC = libmaple/systick.c \
libmaple/usart.c \
libmaple/util.c \
libmaple/usb.c \
+ libmaple/rcc.c \
core/wiring.c \
core/wiring_shift.c \
core/wiring_analog.c \
diff --git a/core/wiring.c b/core/wiring.c
index 04de78a..488d15c 100644
--- a/core/wiring.c
+++ b/core/wiring.c
@@ -25,30 +25,20 @@
#include "wiring.h"
#include "stm32f10x_flash.h"
-#include "stm32f10x_rcc.h"
#include "stm32f10x_map.h"
#include "stm32f10x_nvic.h"
+#include "rcc.h"
#include "systick.h"
#include "gpio.h"
-void RCC_Configuration(void);
void NVIC_Configuration(void);
void init(void) {
- RCC_Configuration();
- RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA |
- RCC_APB2Periph_GPIOB |
- RCC_APB2Periph_GPIOC |
- RCC_APB2Periph_AFIO
- , ENABLE);
+ rcc_init();
NVIC_Configuration();
-
systick_init();
-
gpio_init();
-
adc_init();
-
timer_init(1, 1);
timer_init(2, 1);
timer_init(3, 1);
@@ -57,60 +47,14 @@ void init(void) {
void NVIC_Configuration(void) {
#ifdef VECT_TAB_ROM
- NVIC_SetVectorTable(USER_ADDR_ROM, 0x0);
+ NVIC_SetVectorTable(USER_ADDR_ROM, 0x0);
#warning writing to ROM
#elif defined VECT_TAB_RAM
- NVIC_SetVectorTable(USER_ADDR_RAM, 0x0);
+ NVIC_SetVectorTable(USER_ADDR_RAM, 0x0);
#warning writing to RAM
#else // VECT_TAB_BASE
/* Set the Vector Table base location at 0x08000000 */
- NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
#endif
}
-
-void RCC_Configuration(void) {
- ErrorStatus HSEStartUpStatus;
- /* RCC system reset(for debug purpose) */
- RCC_DeInit();
-
- /* Enable HSE */
- RCC_HSEConfig(RCC_HSE_ON);
-
- /* Wait till HSE is ready */
- HSEStartUpStatus = RCC_WaitForHSEStartUp();
-
- if(HSEStartUpStatus == SUCCESS) {
- /* Enable Prefetch Buffer */
- FLASH_PrefetchBufferCmd( (u32)FLASH_PrefetchBuffer_Enable);
-
- /* Flash 2 wait state */
- FLASH_SetLatency(FLASH_Latency_2);
-
- /* HCLK = SYSCLK */
- RCC_HCLKConfig(RCC_SYSCLK_Div1);
-
- /* PCLK2 = HCLK APB2 Periphs, no prescaler 72MHz */
- RCC_PCLK2Config(RCC_HCLK_Div1);
-
- /* PCLK1 = HCLK/2 APB1 periphs = 36MHZ*/
- RCC_PCLK1Config(RCC_HCLK_Div2);
-
- /* PLLCLK = 8MHz * 9 = 72 MHz */
- RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
-
- /* Enable PLL */
- RCC_PLLCmd(ENABLE);
-
- /* Wait till PLL is ready */
- while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
- ;
-
- /* Select PLL as system clock source */
- RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
-
- /* Wait till PLL is used as system clock source */
- while(RCC_GetSYSCLKSource() != 0x08)
- ;
- }
-}
diff --git a/libmaple/adc.c b/libmaple/adc.c
index 7169824..d584dba 100644
--- a/libmaple/adc.c
+++ b/libmaple/adc.c
@@ -23,10 +23,9 @@
* @brief Analog to digital converter routines
*/
-#include "stm32f10x_rcc.h"
+#include "libmaple.h"
+#include "rcc.h"
#include "adc.h"
-#include <stdio.h>
-#include <inttypes.h>
/* The ADC input clock is generated from PCLK2/APB2 divided by a prescaler
* and it must not exceed 14MHz.
@@ -59,15 +58,9 @@
* At 55.5 cycles/sample, the external input impedance < 50kOhms*/
void adc_init(void) {
- /* PCLK2 is the APB2 clock */
- RCC_ADCCLKConfig(RCC_PCLK2_Div6);
-
- /* Enable ADC1 clock so that we can talk to it */
- RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
-
- /* Put everything back to power-on defaults */
- RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, ENABLE);
- RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, DISABLE);
+ rcc_set_adc_prescaler(PCLK2_DIV_2);
+ rcc_enable_clk_adc1();
+ rcc_reset_adc1();
ADC_CR1 = 0;
ADC_CR2 = CR2_EXTSEL_SWSTART | CR2_EXTTRIG; // Software triggers conversions
diff --git a/libmaple/gpio.c b/libmaple/gpio.c
index facb514..39341af 100644
--- a/libmaple/gpio.c
+++ b/libmaple/gpio.c
@@ -24,17 +24,15 @@
*/
#include "libmaple.h"
-#include "stm32f10x_rcc.h"
+#include "rcc.h"
#include "gpio.h"
void gpio_init(void) {
- /* Turn on clocks for GPIO */
- RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA |
- RCC_APB2Periph_GPIOB |
- RCC_APB2Periph_GPIOC |
- RCC_APB2Periph_GPIOD |
- RCC_APB2Periph_AFIO,
- ENABLE);
+ rcc_enable_clk_gpioa();
+ rcc_enable_clk_gpiob();
+ rcc_enable_clk_gpioc();
+ rcc_enable_clk_gpiod();
+ rcc_enable_clk_afio();
}
void gpio_set_mode(GPIO_Port* port, uint8 gpio_pin, uint8 mode) {
diff --git a/libmaple/rcc.c b/libmaple/rcc.c
new file mode 100644
index 0000000..bf76eb0
--- /dev/null
+++ b/libmaple/rcc.c
@@ -0,0 +1,113 @@
+/**
+ * @file rcc.c
+ *
+ * @brief Implements pretty much only the basic clock setup on the maple,
+ * exposes a handful of clock enable/disable and peripheral reset commands.
+ */
+
+#include "libmaple.h"
+#include "rcc.h"
+#include "stm32f10x_flash.h"
+
+static void set_ahb_prescaler(uint32_t divider) {
+ uint32_t cfgr = __read(RCC_CFGR);
+
+ cfgr &= ~HPRE;
+
+ switch (divider) {
+ case SYSCLK_DIV_1:
+ cfgr |= SYSCLK_DIV_1;
+ break;
+ default:
+ ASSERT(0);
+ }
+
+ __write(RCC_CFGR, cfgr);
+}
+
+static void set_apb1_prescaler(uint32_t divider) {
+ uint32_t cfgr = __read(RCC_CFGR);
+
+ cfgr &= ~PPRE1;
+
+ switch (divider) {
+ case HCLK_DIV_2:
+ cfgr |= HCLK_DIV_2;
+ break;
+ default:
+ ASSERT(0);
+ }
+
+ __write(RCC_CFGR, cfgr);
+}
+
+static void set_apb2_prescaler(uint32_t divider) {
+ uint32_t cfgr = __read(RCC_CFGR);
+
+ cfgr &= ~PPRE2;
+
+ switch (divider) {
+ case HCLK_DIV_1:
+ cfgr |= HCLK_DIV_1;
+ break;
+ default:
+ ASSERT(0);
+ }
+
+ __write(RCC_CFGR, cfgr);
+}
+
+/* FIXME: magic numbers */
+static void pll_init(void) {
+ uint32_t cfgr;
+
+ cfgr = __read(RCC_CFGR);
+ cfgr &= (~PLLMUL | PLL_INPUT_CLK_HSE);
+
+ /* pll multiplier 9, input clock hse */
+ __write(RCC_CFGR, cfgr | PLL_MUL_9 | PLL_INPUT_CLK_HSE);
+
+ /* enable pll */
+ __set_bits(RCC_CR, PLLON);
+ while(!__get_bits(RCC_CR, PLLRDY)) {
+ asm volatile("nop");
+ }
+
+ /* select pll for system clock source */
+ cfgr = __read(RCC_CFGR);
+ cfgr &= ~RCC_CFGR_SWS;
+ __write(RCC_CFGR, cfgr | RCC_CFGR_SWS_PLL);
+
+ while (__get_bits(RCC_CFGR, 0x00000008) != 0x8) {
+ asm volatile("nop");
+ }
+}
+
+static void hse_init(void) {
+ __set_bits(RCC_CR, HSEON);
+ while (!HSERDY) {
+ asm volatile("nop");
+ }
+}
+
+void rcc_init(void) {
+ hse_init();
+
+ /* Leave this here for now... */
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd( (u32)FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ set_ahb_prescaler(SYSCLK_DIV_1);
+ set_apb1_prescaler(HCLK_DIV_2);
+ set_apb2_prescaler(HCLK_DIV_1);
+ pll_init();
+}
+
+void rcc_set_adc_prescaler(uint32_t divider) {
+ uint32_t cfgr = __read(RCC_CFGR);
+ cfgr &= ~ADCPRE;
+ __write(RCC_CFGR, cfgr | PCLK2_DIV_2);
+}
diff --git a/libmaple/rcc.h b/libmaple/rcc.h
new file mode 100644
index 0000000..5c9591b
--- /dev/null
+++ b/libmaple/rcc.h
@@ -0,0 +1,107 @@
+/**
+ * @file rcc.h
+ *
+ * @brief
+ */
+
+#ifndef _RCC_H_
+#define _RCC_H_
+
+#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 HSEON BIT(16)
+#define HSERDY *(volatile uint32_t*)(BITBAND_PERI(RCC_CR + 2, 0))
+
+#define ADCPRE 0x0000C000
+#define HPRE 0x000000F0
+#define PPRE2 0x00003800 // apb2 high speed prescaler
+#define PPRE1 0x00000700 // apb1 low-speed prescaler
+
+#define PLLMUL 0x002C0000
+#define PLL_MUL_9 0x001C0000
+#define PLLSRC BIT(16)
+#define SYSCLK_DIV_1 (0x0 << 4)
+#define HCLK_DIV_1 0
+#define HCLK_DIV_2 0x00000400
+#define PCLK2_DIV_2 0x00008000
+
+#define PLLRDY BIT(25)
+#define PLLON BIT(24)
+#define PLL_INPUT_CLK_HSE BIT(16)
+
+#define RCC_CFGR_SWS 0x00000003
+#define RCC_CFGR_SWS_PLL 0x00000002
+
+/* APB2 reset bits */
+#define RCC_APB2RSTR_USART1RST BIT(14)
+#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_IOERST BIT(6)
+#define RCC_APB2RSTR_IODRST BIT(5)
+#define RCC_APB2RSTR_IOCRST BIT(4)
+#define RCC_APB2RSTR_IOBRST BIT(3)
+#define RCC_APB2RSTR_IOARST BIT(2)
+#define RCC_APB2RSTR_AFIORST BIT(0)
+
+/* APB2 peripheral clock enable bits */
+#define RCC_APB2ENR_USART1EN BIT(14)
+#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_IOEEN BIT(6)
+#define RCC_APB2ENR_IODEN BIT(5)
+#define RCC_APB2ENR_IOCEN BIT(4)
+#define RCC_APB2ENR_IOBEN BIT(3)
+#define RCC_APB2ENR_IOAEN BIT(2)
+#define RCC_APB2ENR_AFIOEN BIT(0)
+
+/* APB1 peripheral clock enable bits */
+#define RCC_APB1ENR_TIM2EN BIT(0)
+#define RCC_APB1ENR_TIM3EN BIT(1)
+#define RCC_APB1ENR_TIM4EN BIT(2)
+#define RCC_APB1ENR_USART2EN BIT(17)
+#define RCC_APB1ENR_USART3EN BIT(18)
+
+#define rcc_enable_clk_timer1() __set_bits(RCC_APB2ENR, RCC_APB2ENR_TIM1EN)
+#define rcc_enable_clk_timer2() __set_bits(RCC_APB1ENR, RCC_APB1ENR_TIM2EN)
+#define rcc_enable_clk_timer3() __set_bits(RCC_APB1ENR, RCC_APB1ENR_TIM3EN)
+#define rcc_enable_clk_timer4() __set_bits(RCC_APB1ENR, RCC_APB1ENR_TIM4EN)
+
+#define rcc_enable_clk_gpioa() __set_bits(RCC_APB2ENR, RCC_APB2ENR_IOAEN)
+#define rcc_enable_clk_gpiob() __set_bits(RCC_APB2ENR, RCC_APB2ENR_IOBEN)
+#define rcc_enable_clk_gpioc() __set_bits(RCC_APB2ENR, RCC_APB2ENR_IOCEN)
+#define rcc_enable_clk_gpiod() __set_bits(RCC_APB2ENR, RCC_APB2ENR_IODEN)
+#define rcc_enable_clk_afio() __set_bits(RCC_APB2ENR, RCC_APB2ENR_AFIOEN)
+
+#define rcc_enable_clk_usart1() __set_bits(RCC_APB2ENR, RCC_APB2ENR_USART1EN)
+#define rcc_enable_clk_usart2() __set_bits(RCC_APB1ENR, RCC_APB1ENR_USART2EN)
+#define rcc_enable_clk_usart3() __set_bits(RCC_APB1ENR, RCC_APB1ENR_USART3EN)
+
+#define rcc_enable_clk_adc1() __set_bits(RCC_APB2ENR, RCC_APB2ENR_ADC1EN)
+
+#define rcc_reset_adc1() { __set_bits(RCC_APB2RSTR, RCC_APB2RSTR_ADC1RST); \
+ __clear_bits(RCC_APB2RSTR, RCC_APB2RSTR_ADC1RST); \
+ }
+
+
+void rcc_init(void);
+void rcc_set_adc_prescaler(uint32_t divider);
+
+#endif
+
+
diff --git a/libmaple/timers.c b/libmaple/timers.c
index 773ae36..e187428 100644
--- a/libmaple/timers.c
+++ b/libmaple/timers.c
@@ -24,7 +24,7 @@
*/
#include "libmaple.h"
-#include "stm32f10x_rcc.h"
+#include "rcc.h"
#include "timers.h"
typedef struct {
@@ -79,20 +79,20 @@ void timer_init(uint8_t timer_num, uint16_t prescale) {
switch(timer_num) {
case 1:
timer = (Timer*)TIMER1_BASE;
- RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE);
+ rcc_enable_clk_timer1();
is_advanced = 1;
break;
case 2:
timer = (Timer*)TIMER2_BASE;
- RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
+ rcc_enable_clk_timer2();
break;
case 3:
timer = (Timer*)TIMER3_BASE;
- RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
+ rcc_enable_clk_timer3();
break;
case 4:
timer = (Timer*)TIMER4_BASE;
- RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE);
+ rcc_enable_clk_timer4();
break;
}
diff --git a/libmaple/usart.c b/libmaple/usart.c
index 9987641..545f64a 100644
--- a/libmaple/usart.c
+++ b/libmaple/usart.c
@@ -24,9 +24,9 @@
*/
#include "libmaple.h"
-#include "stm32f10x_rcc.h"
-#include "usart.h"
+#include "rcc.h"
#include "nvic.h"
+#include "usart.h"
#define USART1_BASE 0x40013800
#define USART2_BASE 0x40004400
@@ -123,21 +123,21 @@ void usart_init(uint8 usart_num, uint32 baud) {
port = (usart_port*)USART1_BASE;
ring_buf = &ring_buf1;
clk_speed = USART1_CLK;
- RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
+ rcc_enable_clk_usart1();
REG_SET(NVIC_ISER1, BIT(5));
break;
case 2:
port = (usart_port*)USART2_BASE;
ring_buf = &ring_buf2;
clk_speed = USART2_CLK;
- RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
+ rcc_enable_clk_usart2();
REG_SET(NVIC_ISER1, BIT(6));
break;
case 3:
port = (usart_port*)USART3_BASE;
ring_buf = &ring_buf3;
clk_speed = USART3_CLK;
- RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
+ rcc_enable_clk_usart3();
REG_SET(NVIC_ISER1, BIT(7));
break;
default:
diff --git a/libmaple/util.h b/libmaple/util.h
index e425cc0..c1ba15d 100644
--- a/libmaple/util.h
+++ b/libmaple/util.h
@@ -54,6 +54,12 @@
#define REG_GET(reg) *(volatile uint32_t*)(reg)
+#define __set_bits(addr, mask) *(volatile uint32_t*)(addr) |= (uint32_t)(mask)
+#define __clear_bits(addr, mask) (*(volatile uint32_t*)(addr) &= (uint32_t)~(mask))
+#define __get_bits(addr, mask) (*(volatile uint32_t*)(addr) & (uint32_t)(mask))
+
+#define __read(reg) *(volatile uint32_t*)(reg)
+#define __write(reg, value) *(volatile uint32_t*)(reg) = (value)
#ifdef __cplusplus
extern "C"{
diff --git a/stm32lib/inc/stm32f10x_map.h b/stm32lib/inc/stm32f10x_map.h
index 3dabb05..16dc479 100644
--- a/stm32lib/inc/stm32f10x_map.h
+++ b/stm32lib/inc/stm32f10x_map.h
@@ -665,7 +665,7 @@ typedef struct
#define DMA2_Channel3_BASE (AHBPERIPH_BASE + 0x0430)
#define DMA2_Channel4_BASE (AHBPERIPH_BASE + 0x0444)
#define DMA2_Channel5_BASE (AHBPERIPH_BASE + 0x0458)
-#define RCC_BASE (AHBPERIPH_BASE + 0x1000)
+//#define RCC_BASE (AHBPERIPH_BASE + 0x1000)
#define CRC_BASE (AHBPERIPH_BASE + 0x3000)
/* Flash registers base address */