Merge pull request #4 from rogerclarkmelbourne/master

Fixes
This commit is contained in:
victorpv 2015-05-23 07:14:03 -05:00
commit 66b3a0394e
15 changed files with 191 additions and 907 deletions

View File

@ -0,0 +1,93 @@
/*
* test-rtc.c
*
* Example program that sets up the Real Time Clock and then blinks the
* LED in patterns for seconds and alarm interrupts.
*
* Created by Rod Gilchrist on 11-12-24.
Ray Burnette: 20150521:
Edited: \Documents\Arduino\hardware\STM32\STM32F1\system\libmaple\stm32f1\include\series\rcc.h to include:
#include <libmaple/bitband.h>
#define RCC_BDCR_RTCSEL_LSI (0x2 << 8)
static inline void rcc_start_lsi(void)
static inline void rcc_start_lse(void)
static inline void rcc_start_hse(void)
Arduino GUI 1.7.3 from Arduino.org
Sketch uses 20,268 bytes (18%) of program storage space. Maximum is 110,592 bytes.
Global variables use 4,552 bytes of dynamic memory.
*/
#include "RTClock.h"
#define BOARD_LED_PIN PB1
int globAlmCnt = 0;
int globOvCnt = 0;
int globSecCnt = 0;
int specAlmCnt = 0;
int lastGlobAlmCnt = -1;
int lastSpecAlmCnt = -1;
void rtc_sec_intr() { if (rtc_is_second()) globSecCnt++; }
void rtc_ovf_intr() { if (rtc_is_overflow()) globOvCnt++; }
void rtc_glob_alm_intr() { if (rtc_is_alarm()) globAlmCnt++; }
void rtc_spec_alm_intr() { if (rtc_is_alarm()) specAlmCnt++; }
void setup() {
// http://forums.leaflabs.com/topic.php?id=1437
// slow! div speed. NOTE! 512 is stop/hang when USB not connected!
// rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_256);
// Normal speed:
// rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1);
pinMode(BOARD_LED_PIN, OUTPUT);
delay(5000);
Serial.println("begin RTC blink");
delay(1000);
rtc_init(RTCSEL_LSI);
rtc_set_prescaler_load(0x7fff);
rtc_set_count(0);
rtc_attach_interrupt(RTC_SECONDS_INTERRUPT, rtc_sec_intr);
rtc_attach_interrupt(RTC_OVERFLOW_INTERRUPT, rtc_ovf_intr); // expected every 128000 seconds
rtc_attach_interrupt(RTC_ALARM_GLOBAL_INTERRUPT, rtc_glob_alm_intr);
rtc_attach_interrupt(RTC_ALARM_SPECIFIC_INTERRUPT, rtc_spec_alm_intr);
}
void loop() {
int i,n;
Serial.print("Time + interrupt counts: ");
Serial.print(rtc_get_count());
Serial.print(".");
Serial.print(rtc_get_divider());
Serial.print(" (");
Serial.print(globSecCnt);
Serial.print(", ");
Serial.print(globOvCnt);
Serial.print(", ");
Serial.print(globAlmCnt);
Serial.print(", ");
Serial.print(specAlmCnt);
Serial.println(")");
delay(1000);
digitalWrite(BOARD_LED_PIN, 1);
if ((lastSpecAlmCnt != specAlmCnt) || (lastGlobAlmCnt != globAlmCnt)){
lastGlobAlmCnt = globAlmCnt;
lastSpecAlmCnt = specAlmCnt;
Serial.println(" -- alarm -- ");
for (i=0;i<3;i++) { digitalWrite(BOARD_LED_PIN, 0); delay(100); digitalWrite(BOARD_LED_PIN, 1); delay(100);}
n = rtc_get_count() + 5;
rtc_set_alarm(n);
}
delay(1000);
digitalWrite(BOARD_LED_PIN, 0);
}

View File

@ -0,0 +1,33 @@
#include <RTClock.h>
RTClock rt (RTCSEL_LSE); // initialise
uint32 tt;
#define LED_PIN PB1
// This function is called in the attachSecondsInterrpt
void blink ()
{
digitalWrite(LED_PIN,!digitalRead(LED_PIN));
}
void setup()
{
pinMode(LED_PIN, OUTPUT);
rt.attachSecondsInterrupt(blink);// Call blink
}
void loop()
{
if (rt.getTime()!=tt)
{
tt = rt.getTime();
Serial.print("time is: ");
Serial.println(tt);
}
}

View File

@ -0,0 +1,23 @@
#######################################
# Syntax Coloring Map RTClock
#######################################
#######################################
# Datatypes (KEYWORD1)
#######################################
RTClock KEYWORD1
setTime KEYWORD2
getTime KEYWORD2
createAlarm KEYWORD2
attachSecondsInterrupt KEYWORD2
detachSecondsInterrupt KEYWORD2
setAlarmTime KEYWORD2
#######################################
# Constants (LITERAL1)
#######################################

View File

@ -0,0 +1,8 @@
name=RTClock
version=1.0
author=Various
email=
sentence=Real Time Clock
paragraph=Real Time Clock for STM32F1
url=
architectures=STM32F1

View File

@ -1,4 +1,6 @@
#include "utility/rtc_util.h"
#include <utility/rtc_util.h>
#include <libmaple/rcc.h>
#include <libmaple/bitband.h>
#include <time.h>

View File

@ -34,13 +34,13 @@
#ifndef _RTC_UTIL_H
#define _RTC_UTIL_H
#include <libmaple\libmaple.h>
#include <libmaple\rcc.h>
#include <libmaple\nvic.h>
#include <libmaple\bitband.h>
#include <libmaple\pwr.h>
#include <libmaple\bkp.h>
#include <libmaple\exti.h>
#include <libmaple/libmaple.h>
#include <libmaple/rcc.h>
#include <libmaple/nvic.h>
#include <libmaple/bitband.h>
#include <libmaple/pwr.h>
#include <libmaple/bkp.h>
#include <libmaple/exti.h>
#define EXTI_RTC_ALARM_BIT 17 // the extra exti interrupts (16,17,18,19) should be defined in exti.h (BUG)

View File

@ -1,19 +0,0 @@
Real Time Clock implementation for the STM32F1xx family of microcontrollers.
It has been tested in:
- Maple
- Maple Mini
- Olimexino.
RTClockTest.pde is an example to use all the features in the library.
Instructions:
- Copy the folder to the MapleIDE\libraries folder. You may have to create a new folder named libraries
- Copy the files in the New RCC folder and replace the same files in your libmaple installation with them.
- Open the example PDE
- Compile, Download and Test.

View File

@ -1,27 +0,0 @@
#include <RTClock.h>
//#include <time.h>
RTClock rt (RTCSEL_LSE);
uint32 tt;
//time_t timer;
void blink () {
toggleLED();
}
void setup() {
pinMode(PB1, OUTPUT);// Roger Clark. Updated for removal of LED pin as a global define (PB1 is Maple mini LED Pin)
rt.attachSecondsInterrupt(blink);
}
void loop() {
tt = rt.getTime();
SerialUSB.print("time is: ");
SerialUSB.println(tt);
// toggleLED();
}

View File

@ -1,204 +0,0 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @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"
#define APB1 RCC_APB1
#define APB2 RCC_APB2
#define AHB RCC_AHB
struct rcc_dev_info {
const rcc_clk_domain clk_domain;
const uint8 line_num;
};
/* Device descriptor table, maps rcc_clk_id onto bus and enable/reset
* register bit numbers. */
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_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_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_I2C1] = { .clk_domain = APB1, .line_num = 21 },
[RCC_I2C2] = { .clk_domain = APB1, .line_num = 22 },
[RCC_CRC] = { .clk_domain = AHB, .line_num = 6},
[RCC_FLITF] = { .clk_domain = AHB, .line_num = 4},
[RCC_SRAM] = { .clk_domain = AHB, .line_num = 2},
#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
[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_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_FSMC] = { .clk_domain = AHB, .line_num = 8 },
[RCC_DAC] = { .clk_domain = APB1, .line_num = 29 },
[RCC_DMA2] = { .clk_domain = AHB, .line_num = 1 },
[RCC_SDIO] = { .clk_domain = AHB, .line_num = 10 },
[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
};
/**
* @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 HSE
* @param pll_mul pll multiplier
*/
void rcc_clk_init(rcc_sysclk_src sysclk_src,
rcc_pllsrc pll_src,
rcc_pll_multiplier pll_mul) {
uint32 cfgr = 0;
uint32 cr;
/* 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_PLLSRC_HSE);
RCC_BASE->CFGR = pll_src | pll_mul;
/* Turn on the HSE */
cr = RCC_BASE->CR;
cr |= RCC_CR_HSEON;
RCC_BASE->CR = cr;
while (!(RCC_BASE->CR & RCC_CR_HSERDY))
;
/* Now the PLL */
cr |= RCC_CR_PLLON;
RCC_BASE->CR = cr;
while (!(RCC_BASE->CR & RCC_CR_PLLRDY))
;
/* Finally, let's switch over to the PLL */
cfgr &= ~RCC_CFGR_SW;
cfgr |= RCC_CFGR_SW_PLL;
RCC_BASE->CFGR = cfgr;
while ((RCC_BASE->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL)
;
}
/**
* @brief Turn on the clock line on a peripheral
* @param id Clock ID of the peripheral to turn on.
*/
void rcc_clk_enable(rcc_clk_id id) {
static const __io uint32* enable_regs[] = {
[APB1] = &RCC_BASE->APB1ENR,
[APB2] = &RCC_BASE->APB2ENR,
[AHB] = &RCC_BASE->AHBENR,
};
rcc_clk_domain clk_domain = rcc_dev_clk(id);
__io uint32* enr = (__io uint32*)enable_regs[clk_domain];
uint8 lnum = rcc_dev_table[id].line_num;
bb_peri_set_bit(enr, lnum, 1);
}
/**
* @brief Reset a peripheral.
* @param id Clock ID of the peripheral to reset.
*/
void rcc_reset_dev(rcc_clk_id id) {
static const __io uint32* reset_regs[] = {
[APB1] = &RCC_BASE->APB1RSTR,
[APB2] = &RCC_BASE->APB2RSTR,
};
rcc_clk_domain clk_domain = rcc_dev_clk(id);
__io void* addr = (__io void*)reset_regs[clk_domain];
uint8 lnum = rcc_dev_table[id].line_num;
bb_peri_set_bit(addr, lnum, 1);
bb_peri_set_bit(addr, lnum, 0);
}
/**
* @brief Get a peripheral's clock domain
* @param id Clock ID of the peripheral whose clock domain to return
* @return Clock source for the given clock ID
*/
rcc_clk_domain rcc_dev_clk(rcc_clk_id id) {
return rcc_dev_table[id].clk_domain;
}
/**
* @brief Set the divider on a peripheral prescaler
* @param prescaler prescaler to set
* @param divider prescaler divider
*/
void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider) {
static const uint32 masks[] = {
[RCC_PRESCALER_AHB] = RCC_CFGR_HPRE,
[RCC_PRESCALER_APB1] = RCC_CFGR_PPRE1,
[RCC_PRESCALER_APB2] = RCC_CFGR_PPRE2,
[RCC_PRESCALER_USB] = RCC_CFGR_USBPRE,
[RCC_PRESCALER_ADC] = RCC_CFGR_ADCPRE,
};
uint32 cfgr = RCC_BASE->CFGR;
cfgr &= ~masks[prescaler];
cfgr |= divider;
RCC_BASE->CFGR = cfgr;
}

View File

@ -1,619 +0,0 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file rcc.h
* @brief reset and clock control definitions and prototypes
*/
#include "libmaple_types.h"
#include "util.h"
#include "bitband.h"
#ifndef _RCC_H_
#define _RCC_H_
#ifdef __cplusplus
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 pointer */
#define RCC_BASE ((struct rcc_reg_map*)0x40021000)
/*
* 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 (0x3 << 24)
#define RCC_CFGR_USBPRE BIT(RCC_CFGR_USBPRE_BIT)
#define RCC_CFGR_PLLMUL (0xF << 18)
#define RCC_CFGR_PLLXTPRE BIT(RCC_CFGR_PLLXTPRE_BIT)
#define RCC_CFGR_PLLSRC BIT(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
#define RCC_CFGR_SW_PLL 0x2
#define RCC_CFGR_SW_HSE 0x1
/* 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_USART3RST_BIT 18
#define RCC_APB1RSTR_USART2RST_BIT 17
#define RCC_APB1RSTR_SPI3RST_BIT 15
#define RCC_APB1RSTR_SPI2RST_BIT 14
#define RCC_APB1RSTR_WWDRST_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_USART3RST BIT(RCC_APB1RSTR_USART3RST_BIT)
#define RCC_APB1RSTR_USART2RST BIT(RCC_APB1RSTR_USART2RST_BIT)
#define RCC_APB1RSTR_SPI3RST BIT(RCC_APB1RSTR_SPI3RST_BIT)
#define RCC_APB1RSTR_SPI2RST BIT(RCC_APB1RSTR_SPI2RST_BIT)
#define RCC_APB1RSTR_WWDRST BIT(RCC_APB1RSTR_WWDRST_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 7
#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_PWREN_BIT 28
#define RCC_APB1ENR_BKPEN_BIT 27
#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_USART3EN_BIT 18
#define RCC_APB1ENR_USART2EN_BIT 17
#define RCC_APB1ENR_SPI3EN_BIT 15
#define RCC_APB1ENR_SPI2EN_BIT 14
#define RCC_APB1ENR_WWDEN_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_USART3EN BIT(RCC_APB1ENR_USART3EN_BIT)
#define RCC_APB1ENR_USART2EN BIT(RCC_APB1ENR_USART2EN_BIT)
#define RCC_APB1ENR_SPI3EN BIT(RCC_APB1ENR_SPI3EN_BIT)
#define RCC_APB1ENR_SPI2EN BIT(RCC_APB1ENR_SPI2EN_BIT)
#define RCC_APB1ENR_WWDEN BIT(RCC_APB1ENR_WWDEN_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_BI)
#define RCC_BDCR_RTCSEL (0x3 << 8)
#define RCC_BDCR_RTCSEL_NONE (0x0 << 8)
#define RCC_BDCR_RTCSEL_LSE (0x1 << 8)
#define RCC_BDCR_RTCSEL_LSI (0x2 << 8)
#define RCC_BDCR_RTCSEL_HSE (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 24
#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)
/*
* Convenience routines
*/
/**
* SYSCLK sources
* @see rcc_clk_init()
*/
typedef enum rcc_sysclk_src {
RCC_CLKSRC_HSI = 0x0,
RCC_CLKSRC_HSE = 0x1,
RCC_CLKSRC_PLL = 0x2,
} rcc_sysclk_src;
/**
* PLL entry clock source
* @see rcc_clk_init()
*/
typedef enum rcc_pllsrc {
RCC_PLLSRC_HSE = (0x1 << 16),
RCC_PLLSRC_HSI_DIV_2 = (0x0 << 16)
} rcc_pllsrc;
/**
* PLL multipliers
* @see rcc_clk_init()
*/
typedef enum rcc_pll_multiplier {
RCC_PLLMUL_2 = (0x0 << 18),
RCC_PLLMUL_3 = (0x1 << 18),
RCC_PLLMUL_4 = (0x2 << 18),
RCC_PLLMUL_5 = (0x3 << 18),
RCC_PLLMUL_6 = (0x4 << 18),
RCC_PLLMUL_7 = (0x5 << 18),
RCC_PLLMUL_8 = (0x6 << 18),
RCC_PLLMUL_9 = (0x7 << 18),
RCC_PLLMUL_10 = (0x8 << 18),
RCC_PLLMUL_11 = (0x9 << 18),
RCC_PLLMUL_12 = (0xA << 18),
RCC_PLLMUL_13 = (0xB << 18),
RCC_PLLMUL_14 = (0xC << 18),
RCC_PLLMUL_15 = (0xD << 18),
RCC_PLLMUL_16 = (0xE << 18),
} rcc_pll_multiplier;
/**
* @brief Identifies bus and clock line for a peripheral.
*
* Also generally useful as a unique identifier for that peripheral
* (or its corresponding device struct).
*/
typedef enum rcc_clk_id {
RCC_GPIOA,
RCC_GPIOB,
RCC_GPIOC,
RCC_GPIOD,
RCC_AFIO,
RCC_ADC1,
RCC_ADC2,
RCC_ADC3,
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_I2C1,
RCC_I2C2,
RCC_CRC,
RCC_FLITF,
RCC_SRAM,
RCC_USB,
#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
RCC_GPIOE,
RCC_GPIOF,
RCC_GPIOG,
RCC_UART4,
RCC_UART5,
RCC_TIMER5,
RCC_TIMER6,
RCC_TIMER7,
RCC_TIMER8,
RCC_FSMC,
RCC_DAC,
RCC_DMA2,
RCC_SDIO,
RCC_SPI3,
#endif
#ifdef STM32_XL_DENSITY
RCC_TIMER9,
RCC_TIMER10,
RCC_TIMER11,
RCC_TIMER12,
RCC_TIMER13,
RCC_TIMER14,
#endif
} rcc_clk_id;
void rcc_clk_init(rcc_sysclk_src sysclk_src,
rcc_pllsrc pll_src,
rcc_pll_multiplier pll_mul);
void rcc_clk_enable(rcc_clk_id device);
void rcc_reset_dev(rcc_clk_id device);
typedef enum rcc_clk_domain {
RCC_APB1,
RCC_APB2,
RCC_AHB
} rcc_clk_domain;
rcc_clk_domain rcc_dev_clk(rcc_clk_id device);
/**
* Prescaler identifiers
* @see rcc_set_prescaler()
*/
typedef enum rcc_prescaler {
RCC_PRESCALER_AHB,
RCC_PRESCALER_APB1,
RCC_PRESCALER_APB2,
RCC_PRESCALER_USB,
RCC_PRESCALER_ADC
} rcc_prescaler;
/**
* ADC prescaler dividers
* @see rcc_set_prescaler()
*/
typedef enum rcc_adc_divider {
RCC_ADCPRE_PCLK_DIV_2 = 0x0 << 14,
RCC_ADCPRE_PCLK_DIV_4 = 0x1 << 14,
RCC_ADCPRE_PCLK_DIV_6 = 0x2 << 14,
RCC_ADCPRE_PCLK_DIV_8 = 0x3 << 14,
} rcc_adc_divider;
/**
* APB1 prescaler dividers
* @see rcc_set_prescaler()
*/
typedef enum rcc_apb1_divider {
RCC_APB1_HCLK_DIV_1 = 0x0 << 8,
RCC_APB1_HCLK_DIV_2 = 0x4 << 8,
RCC_APB1_HCLK_DIV_4 = 0x5 << 8,
RCC_APB1_HCLK_DIV_8 = 0x6 << 8,
RCC_APB1_HCLK_DIV_16 = 0x7 << 8,
} rcc_apb1_divider;
/**
* APB2 prescaler dividers
* @see rcc_set_prescaler()
*/
typedef enum rcc_apb2_divider {
RCC_APB2_HCLK_DIV_1 = 0x0 << 11,
RCC_APB2_HCLK_DIV_2 = 0x4 << 11,
RCC_APB2_HCLK_DIV_4 = 0x5 << 11,
RCC_APB2_HCLK_DIV_8 = 0x6 << 11,
RCC_APB2_HCLK_DIV_16 = 0x7 << 11,
} rcc_apb2_divider;
/**
* AHB prescaler dividers
* @see rcc_set_prescaler()
*/
typedef enum rcc_ahb_divider {
RCC_AHB_SYSCLK_DIV_1 = 0x0 << 4,
RCC_AHB_SYSCLK_DIV_2 = 0x8 << 4,
RCC_AHB_SYSCLK_DIV_4 = 0x9 << 4,
RCC_AHB_SYSCLK_DIV_8 = 0xA << 4,
RCC_AHB_SYSCLK_DIV_16 = 0xB << 4,
RCC_AHB_SYSCLK_DIV_32 = 0xC << 4,
RCC_AHB_SYSCLK_DIV_64 = 0xD << 4,
RCC_AHB_SYSCLK_DIV_128 = 0xD << 4,
RCC_AHB_SYSCLK_DIV_256 = 0xE << 4,
RCC_AHB_SYSCLK_DIV_512 = 0xF << 4,
} rcc_ahb_divider;
void rcc_set_prescaler(rcc_prescaler prescaler, uint32 divider);
/**
* @brief Start the low speed internal oscillatior
*/
static inline void rcc_start_lsi(void) {
*bb_perip(&RCC_BASE->CSR, RCC_CSR_LSION_BIT) = 1;
while (*bb_perip(&RCC_BASE->CSR, RCC_CSR_LSIRDY_BIT) == 0);
}
/**
* @brief Stop the low speed internal oscillatior
*/
static inline void rcc_stop_lsi(void) {
*bb_perip(&RCC_BASE->CSR, RCC_CSR_LSION_BIT) = 0;
}
/**
* @brief Start the low speed external oscillatior
*/
static inline void rcc_start_lse(void) {
bb_peri_set_bit(&RCC_BASE->BDCR, RCC_BDCR_LSEBYP_BIT, 0);
bb_peri_set_bit(&RCC_BASE->BDCR, RCC_BDCR_LSEON_BIT, 1);
while (bb_peri_get_bit(&RCC_BASE->BDCR, RCC_BDCR_LSERDY_BIT ) == 0);
}
/**
* @brief Stop the low speed external oscillatior
*/
static inline void rcc_stop_lse(void) {
bb_peri_set_bit(&RCC_BASE->BDCR, RCC_BDCR_LSEON, 0);
}
/**
* @brief Start the high speed external oscillatior
*/
static inline void rcc_start_hse(void) {
// *bb_perip(&RCC_BASE->CR, RCC_CR_HSEON_BIT) = 1;
while (bb_peri_get_bit(&RCC_BASE->CR, RCC_CR_HSERDY_BIT) == 0);
}
/**
* @brief Stop the high speed external oscillatior
*/
static inline void rcc_stop_hse(void) {
// *bb_perip(&RCC_BASE->CR, RCC_CR_HSEON_BIT) = 0;
}
#ifdef __cplusplus
} // extern "C"
#endif
#endif

View File

@ -1,29 +0,0 @@
# Standard things
sp := $(sp).x
dirstack_$(sp) := $(d)
d := $(dir)
BUILDDIRS += $(BUILD_PATH)/$(d)
# Local flags
CFLAGS_$(d) := $(WIRISH_INCLUDES) $(LIBMAPLE_INCLUDES)
# Local rules and targets
cSRCS_$(d) := utility/rtc_util.c
cppSRCS_$(d) := RTClock.cpp
cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%)
cppFILES_$(d) := $(cppSRCS_$(d):%=$(d)/%)
OBJS_$(d) := $(cFILES_$(d):%.c=$(BUILD_PATH)/%.o) \
$(cppFILES_$(d):%.cpp=$(BUILD_PATH)/%.o)
DEPS_$(d) := $(OBJS_$(d):%.o=%.d)
$(OBJS_$(d)): TGT_CFLAGS := $(CFLAGS_$(d))
TGT_BIN += $(OBJS_$(d))
# Standard things
-include $(DEPS_$(d))
d := $(dirstack_$(sp))
sp := $(basename $(sp))

View File

@ -91,7 +91,8 @@ recipe.S.o.pattern="{compiler.path}{compiler.c.cmd}" {compiler.S.flags} -mcpu={b
recipe.ar.pattern="{compiler.path}{compiler.ar.cmd}" {compiler.ar.flags} {compiler.ar.extra_flags} "{build.path}/{archive_file}" "{object_file}"
## Combine gc-sections, archives, and objects
recipe.c.combine.pattern="{compiler.path}{compiler.c.elf.cmd}" {compiler.c.elf.flags} -mcpu={build.mcu} "-T{build.variant.path}/{build.ldscript}" "-Wl,-Map,{build.path}/{build.project_name}.map" {compiler.c.elf.extra_flags} -o "{build.path}/{build.project_name}.elf" "-L{build.path}" -lm -lgcc -mthumb -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--unresolved-symbols=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--warn-unresolved-symbols -Wl,--start-group {object_files} "{build.path}/{archive_file}" -Wl,--end-group
#recipe.c.combine.pattern="{compiler.path}{compiler.c.elf.cmd}" {compiler.c.elf.flags} -mcpu={build.mcu} "-T{build.variant.path}/{build.ldscript}" "-Wl,-Map,{build.path}/{build.project_name}.map" {compiler.c.elf.extra_flags} -o "{build.path}/{build.project_name}.elf" "-L{build.path}" -lm -lgcc -mthumb -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--unresolved-symbols=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--warn-unresolved-symbols -Wl,--start-group {object_files} "{build.path}/{archive_file}" -Wl,--end-group
recipe.c.combine.pattern="{compiler.path}{compiler.c.elf.cmd}" {compiler.c.elf.flags} -mcpu={build.mcu} "-T{build.variant.path}/{build.ldscript}" "-Wl,-Map,{build.path}/{build.project_name}.map" {compiler.c.elf.extra_flags} -o "{build.path}/{build.project_name}.elf" "-L{build.path}" -lm -lgcc -mthumb -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--unresolved-symbols=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--warn-unresolved-symbols -Wl,--start-group {object_files} -Wl,--whole-archive "{build.path}/{archive_file}" -Wl,--no-whole-archive -Wl,--end-group
## Create eeprom
recipe.objcopy.eep.pattern=

View File

@ -38,6 +38,7 @@ extern "C"{
#endif
#include <libmaple/libmaple_types.h>
#include <libmaple/bitband.h>
/*
* Register map
@ -356,6 +357,7 @@ typedef struct rcc_reg_map {
#define RCC_BDCR_RTCSEL (0x3 << 8)
#define RCC_BDCR_RTCSEL_NONE (0x0 << 8)
#define RCC_BDCR_RTCSEL_LSE (0x1 << 8)
#define RCC_BDCR_RTCSEL_LSI (0x2 << 8) // added to support RTClock
#define RCC_BDCR_RTCSEL_HSE (0x3 << 8)
#define RCC_BDCR_LSEBYP (1U << RCC_BDCR_LSEBYP_BIT)
#define RCC_BDCR_LSERDY (1U << RCC_BDCR_LSERDY_BIT)
@ -522,6 +524,14 @@ typedef enum rcc_ahb_divider {
RCC_AHB_SYSCLK_DIV_512 = 0xF << 4,
} rcc_ahb_divider;
/**
* @brief Start the low speed internal oscillatior
*/
static inline void rcc_start_lsi(void) {
*bb_perip(&RCC_BASE->CSR, RCC_CSR_LSION_BIT) = 1;
while (*bb_perip(&RCC_BASE->CSR, RCC_CSR_LSIRDY_BIT) == 0);
}
/**
* @brief STM32F1 clock sources.
*/
@ -563,6 +573,14 @@ typedef enum rcc_pll_multiplier {
} rcc_pll_multiplier;
/* FIXME [0.0.13] Just have data point to an rcc_pll_multiplier! */
/**
* @brief Start the low speed external oscillatior
*/
static inline void rcc_start_lse(void) {
bb_peri_set_bit(&RCC_BASE->BDCR, RCC_BDCR_LSEBYP_BIT, 0);
bb_peri_set_bit(&RCC_BASE->BDCR, RCC_BDCR_LSEON_BIT, 1);
while (bb_peri_get_bit(&RCC_BASE->BDCR, RCC_BDCR_LSERDY_BIT ) == 0);
}
/**
* @brief STM32F1 PLL configuration values.
@ -576,6 +594,10 @@ typedef struct stm32f1_rcc_pll_data {
/*
* Deprecated bits.
*/
static inline void rcc_start_hse(void) { // Added to support RTClock
// *bb_perip(&RCC_BASE->CR, RCC_CR_HSEON_BIT) = 1;
while (bb_peri_get_bit(&RCC_BASE->CR, RCC_CR_HSERDY_BIT) == 0);
}
/**
* @brief Deprecated; STM32F1 only.