Add more RTC functions and an RTC example.
Thanks Lord James <lordjames@y7mail.com> for the patch!
This commit is contained in:
parent
8195b1a718
commit
93fe67908a
@ -24,7 +24,7 @@ Q := @
|
|||||||
MAKEFLAGS += --no-print-directory
|
MAKEFLAGS += --no-print-directory
|
||||||
endif
|
endif
|
||||||
|
|
||||||
all: i2c_stts75_sensor adc_temperature_sensor dma_mem2mem timer_interrupt systick dogm128
|
all: i2c_stts75_sensor adc_temperature_sensor dma_mem2mem timer_interrupt systick dogm128 rtc
|
||||||
|
|
||||||
i2c_stts75_sensor:
|
i2c_stts75_sensor:
|
||||||
@printf " BUILD examples/other/i2c_stts75_sensor\n"
|
@printf " BUILD examples/other/i2c_stts75_sensor\n"
|
||||||
@ -50,6 +50,10 @@ dogm128:
|
|||||||
@printf " BUILD examples/other/dogm128\n"
|
@printf " BUILD examples/other/dogm128\n"
|
||||||
$(Q)$(MAKE) -C dogm128
|
$(Q)$(MAKE) -C dogm128
|
||||||
|
|
||||||
|
rtc:
|
||||||
|
@printf " BUILD examples/other/rtc\n"
|
||||||
|
$(Q)$(MAKE) -C rtc
|
||||||
|
|
||||||
clean:
|
clean:
|
||||||
@printf " CLEAN examples/other/i2c_stts75_sensor\n"
|
@printf " CLEAN examples/other/i2c_stts75_sensor\n"
|
||||||
$(Q)$(MAKE) -C i2c_stts75_sensor clean
|
$(Q)$(MAKE) -C i2c_stts75_sensor clean
|
||||||
@ -63,6 +67,8 @@ clean:
|
|||||||
$(Q)$(MAKE) -C systick clean
|
$(Q)$(MAKE) -C systick clean
|
||||||
@printf " CLEAN examples/other/dogm128\n"
|
@printf " CLEAN examples/other/dogm128\n"
|
||||||
$(Q)$(MAKE) -C dogm128 clean
|
$(Q)$(MAKE) -C dogm128 clean
|
||||||
|
@printf " CLEAN examples/other/rtc\n"
|
||||||
|
$(Q)$(MAKE) -C rtc clean
|
||||||
|
|
||||||
.PHONY: i2c_stts75_sensor adc_temperature_sensor dma_mem2mem timer_interrupt systick dogm128 clean
|
.PHONY: i2c_stts75_sensor adc_temperature_sensor dma_mem2mem timer_interrupt systick dogm128 rtc clean
|
||||||
|
|
||||||
|
95
examples/other/rtc/Makefile
Normal file
95
examples/other/rtc/Makefile
Normal file
@ -0,0 +1,95 @@
|
|||||||
|
##
|
||||||
|
## This file is part of the libopenstm32 project.
|
||||||
|
##
|
||||||
|
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
|
||||||
|
##
|
||||||
|
## This program is free software: you can redistribute it and/or modify
|
||||||
|
## it under the terms of the GNU General Public License as published by
|
||||||
|
## the Free Software Foundation, either version 3 of the License, or
|
||||||
|
## (at your option) any later version.
|
||||||
|
##
|
||||||
|
## This program 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 General Public License for more details.
|
||||||
|
##
|
||||||
|
## You should have received a copy of the GNU General Public License
|
||||||
|
## along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
##
|
||||||
|
|
||||||
|
BINARY = rtc
|
||||||
|
|
||||||
|
# PREFIX ?= arm-none-eabi
|
||||||
|
PREFIX ?= arm-elf
|
||||||
|
CC = $(PREFIX)-gcc
|
||||||
|
LD = $(PREFIX)-ld
|
||||||
|
OBJCOPY = $(PREFIX)-objcopy
|
||||||
|
OBJDUMP = $(PREFIX)-objdump
|
||||||
|
# Uncomment this line if you want to use the installed (not local) library.
|
||||||
|
# TOOLCHAIN_DIR = `dirname \`which $(CC)\``/../$(PREFIX)
|
||||||
|
TOOLCHAIN_DIR = ../../..
|
||||||
|
CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
|
||||||
|
-mcpu=cortex-m3 -mthumb
|
||||||
|
LDSCRIPT = $(BINARY).ld
|
||||||
|
LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
|
||||||
|
OBJS = $(BINARY).o
|
||||||
|
|
||||||
|
OPENOCD_BASE = /usr
|
||||||
|
OPENOCD = $(OPENOCD_BASE)/bin/openocd
|
||||||
|
OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
|
||||||
|
OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/parport.cfg
|
||||||
|
OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/olimex_stm32_h103.cfg
|
||||||
|
|
||||||
|
# Be silent per default, but 'make V=1' will show all compiler calls.
|
||||||
|
ifneq ($(V),1)
|
||||||
|
Q := @
|
||||||
|
NULL := 2>/dev/null
|
||||||
|
endif
|
||||||
|
|
||||||
|
all: images
|
||||||
|
|
||||||
|
images: $(BINARY)
|
||||||
|
@printf " OBJCOPY $(BINARY).bin\n"
|
||||||
|
$(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
|
||||||
|
@printf " OBJCOPY $(BINARY).hex\n"
|
||||||
|
$(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
|
||||||
|
@printf " OBJCOPY $(BINARY).srec\n"
|
||||||
|
$(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
|
||||||
|
@printf " OBJDUMP $(BINARY).list\n"
|
||||||
|
$(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
|
||||||
|
|
||||||
|
$(BINARY): $(OBJS) $(LDSCRIPT)
|
||||||
|
@printf " LD $(subst $(shell pwd)/,,$(@))\n"
|
||||||
|
$(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
|
||||||
|
|
||||||
|
%.o: %.c Makefile
|
||||||
|
@printf " CC $(subst $(shell pwd)/,,$(@))\n"
|
||||||
|
$(Q)$(CC) $(CFLAGS) -o $@ -c $<
|
||||||
|
|
||||||
|
clean:
|
||||||
|
@printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
|
||||||
|
$(Q)rm -f *.o
|
||||||
|
@printf " CLEAN $(BINARY)\n"
|
||||||
|
$(Q)rm -f $(BINARY)
|
||||||
|
@printf " CLEAN $(BINARY).bin\n"
|
||||||
|
$(Q)rm -f $(BINARY).bin
|
||||||
|
@printf " CLEAN $(BINARY).hex\n"
|
||||||
|
$(Q)rm -f $(BINARY).hex
|
||||||
|
@printf " CLEAN $(BINARY).srec\n"
|
||||||
|
$(Q)rm -f $(BINARY).srec
|
||||||
|
@printf " CLEAN $(BINARY).list\n"
|
||||||
|
$(Q)rm -f $(BINARY).list
|
||||||
|
|
||||||
|
flash: images
|
||||||
|
@printf " FLASH $(BINARY).bin\n"
|
||||||
|
@# IMPORTANT: Don't use "resume", only "reset" will work correctly!
|
||||||
|
$(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
|
||||||
|
-f $(OPENOCD_FLASHER) \
|
||||||
|
-f $(OPENOCD_BOARD) \
|
||||||
|
-c "init" -c "reset halt" \
|
||||||
|
-c "flash write_image erase $(BINARY).hex" \
|
||||||
|
-c "reset" \
|
||||||
|
-c "shutdown" $(NULL)
|
||||||
|
|
||||||
|
.PHONY: images clean
|
||||||
|
|
43
examples/other/rtc/README
Normal file
43
examples/other/rtc/README
Normal file
@ -0,0 +1,43 @@
|
|||||||
|
------------------------------------------------------------------------------
|
||||||
|
README
|
||||||
|
------------------------------------------------------------------------------
|
||||||
|
|
||||||
|
This is a small RTC example project.
|
||||||
|
|
||||||
|
|
||||||
|
Building
|
||||||
|
--------
|
||||||
|
|
||||||
|
$ make
|
||||||
|
|
||||||
|
Running 'make' on the top-level libopenstm32 directory will automatically
|
||||||
|
also build this example. Or you can build the library "manually" and
|
||||||
|
then run 'make' in this directory.
|
||||||
|
|
||||||
|
You may want to override the toolchain (e.g., arm-elf or arm-none-eabi):
|
||||||
|
|
||||||
|
$ PREFIX=arm-none-eabi make
|
||||||
|
|
||||||
|
For a more verbose build you can use
|
||||||
|
|
||||||
|
$ make V=1
|
||||||
|
|
||||||
|
|
||||||
|
Flashing
|
||||||
|
--------
|
||||||
|
|
||||||
|
You can flash the generated code using OpenOCD:
|
||||||
|
|
||||||
|
$ make flash
|
||||||
|
|
||||||
|
Or you can do the same manually via:
|
||||||
|
|
||||||
|
$ openocd -f interface/jtagkey-tiny.cfg -f board/olimex_stm32_h103.cfg
|
||||||
|
$ telnet localhost 4444
|
||||||
|
> reset halt
|
||||||
|
> flash write_image erase rtc.hex
|
||||||
|
> reset
|
||||||
|
|
||||||
|
Replace the "jtagkey-tiny.cfg" with whatever JTAG device you are using, and/or
|
||||||
|
replace "olimex_stm32_h103.cfg" with your respective board config file.
|
||||||
|
|
116
examples/other/rtc/rtc.c
Normal file
116
examples/other/rtc/rtc.c
Normal file
@ -0,0 +1,116 @@
|
|||||||
|
/*
|
||||||
|
* This file is part of the libopenstm32 project.
|
||||||
|
*
|
||||||
|
* Copyright (C) 2010 Lord James <lordjames@y7mail.com>
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program 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 General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <libopenstm32/rcc.h>
|
||||||
|
#include <libopenstm32/gpio.h>
|
||||||
|
#include <libopenstm32/usart.h>
|
||||||
|
#include <libopenstm32/rtc.h>
|
||||||
|
#include <libopenstm32/pwr.h>
|
||||||
|
#include <libopenstm32/nvic.h>
|
||||||
|
|
||||||
|
void clock_setup(void)
|
||||||
|
{
|
||||||
|
rcc_clock_setup_in_hse_8mhz_out_72mhz();
|
||||||
|
|
||||||
|
/* Enable GPIOC clock. */
|
||||||
|
rcc_peripheral_enable_clock(&RCC_APB2ENR, IOPCEN);
|
||||||
|
|
||||||
|
/* Enable clocks for GPIO port A (for GPIO_USART1_TX) and USART1. */
|
||||||
|
rcc_peripheral_enable_clock(&RCC_APB2ENR, IOPAEN);
|
||||||
|
rcc_peripheral_enable_clock(&RCC_APB2ENR, USART1EN);
|
||||||
|
}
|
||||||
|
|
||||||
|
void usart_setup(void)
|
||||||
|
{
|
||||||
|
/* Setup GPIO pin GPIO_USART1_TX/GPIO9 on GPIO port A for transmit. */
|
||||||
|
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_TX);
|
||||||
|
|
||||||
|
/* Setup UART parameters. */
|
||||||
|
usart_set_baudrate(USART1, 38400);
|
||||||
|
usart_set_databits(USART1, 8);
|
||||||
|
usart_set_stopbits(USART1, USART_STOPBITS_1);
|
||||||
|
usart_set_mode(USART1, USART_MODE_TX);
|
||||||
|
usart_set_parity(USART1, USART_PARITY_NONE);
|
||||||
|
usart_set_flow_control(USART1, USART_FLOWCONTROL_NONE);
|
||||||
|
|
||||||
|
/* Finally enable the USART. */
|
||||||
|
usart_enable(USART1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void gpio_setup(void)
|
||||||
|
{
|
||||||
|
/* Set GPIO12 (in GPIO port C) to 'output push-pull'. */
|
||||||
|
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
|
||||||
|
GPIO_CNF_OUTPUT_PUSHPULL, GPIO12);
|
||||||
|
}
|
||||||
|
|
||||||
|
void nvic_setup(void)
|
||||||
|
{
|
||||||
|
/* Without this the RTC interrupt routine will never be called. */
|
||||||
|
nvic_enable_irq(NVIC_RTC_IRQ);
|
||||||
|
nvic_set_priority(NVIC_RTC_IRQ, 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void rtc_isr(void)
|
||||||
|
{
|
||||||
|
volatile u32 j = 0, c = 0;
|
||||||
|
|
||||||
|
/* The interrupt flag isn't cleared by hardware, we have to do it. */
|
||||||
|
rtc_clear_flag(RTC_SEC);
|
||||||
|
|
||||||
|
/* Visual output. */
|
||||||
|
gpio_toggle(GPIOC, GPIO12);
|
||||||
|
|
||||||
|
c = rtc_get_counter_val();
|
||||||
|
|
||||||
|
/* Display the current counter value in binary via USART1. */
|
||||||
|
for (j = 0; j < 32; j++) {
|
||||||
|
if ((c & (0x80000000 >> j)) != 0) {
|
||||||
|
usart_send(USART1, '1');
|
||||||
|
} else {
|
||||||
|
usart_send(USART1, '0');
|
||||||
|
}
|
||||||
|
}
|
||||||
|
usart_send(USART1, '\n');
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(void)
|
||||||
|
{
|
||||||
|
clock_setup();
|
||||||
|
gpio_setup();
|
||||||
|
usart_setup();
|
||||||
|
|
||||||
|
/*
|
||||||
|
* If the RTC is pre-configured just allow access, don't reconfigure.
|
||||||
|
* Otherwise enable it with the LSE as clock source and 0x7fff as
|
||||||
|
* prescale value.
|
||||||
|
*/
|
||||||
|
rtc_auto_awake(LSE, 0x7fff);
|
||||||
|
|
||||||
|
/* Setup the RTC interrupt. */
|
||||||
|
nvic_setup();
|
||||||
|
|
||||||
|
/* Enable the RTC interrupt to occur off the SEC flag. */
|
||||||
|
rtc_interrupt_enable(RTC_SEC);
|
||||||
|
|
||||||
|
while(1);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
31
examples/other/rtc/rtc.ld
Normal file
31
examples/other/rtc/rtc.ld
Normal file
@ -0,0 +1,31 @@
|
|||||||
|
/*
|
||||||
|
* This file is part of the libopenstm32 project.
|
||||||
|
*
|
||||||
|
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program 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 General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Linker script for Olimex STM32-H103 (STM32F103RBT6, 128K flash, 20K RAM). */
|
||||||
|
|
||||||
|
/* Define memory regions. */
|
||||||
|
MEMORY
|
||||||
|
{
|
||||||
|
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
|
||||||
|
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Include the common ld script from libopenstm32. */
|
||||||
|
INCLUDE libopenstm32.ld
|
||||||
|
|
@ -401,5 +401,6 @@ u32 rcc_get_system_clock_source(int i);
|
|||||||
void rcc_clock_setup_in_hsi_out_64mhz(void);
|
void rcc_clock_setup_in_hsi_out_64mhz(void);
|
||||||
void rcc_clock_setup_in_hse_8mhz_out_72mhz(void);
|
void rcc_clock_setup_in_hse_8mhz_out_72mhz(void);
|
||||||
void rcc_clock_setup_in_hse_16mhz_out_72mhz(void);
|
void rcc_clock_setup_in_hse_16mhz_out_72mhz(void);
|
||||||
|
void rcc_backupdomain_reset(void);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -22,6 +22,7 @@
|
|||||||
|
|
||||||
#include <libopenstm32/memorymap.h>
|
#include <libopenstm32/memorymap.h>
|
||||||
#include <libopenstm32/common.h>
|
#include <libopenstm32/common.h>
|
||||||
|
#include <libopenstm32/pwr.h>
|
||||||
|
|
||||||
/* --- RTC registers ------------------------------------------------------- */
|
/* --- RTC registers ------------------------------------------------------- */
|
||||||
|
|
||||||
@ -120,6 +121,26 @@
|
|||||||
|
|
||||||
/* --- Function prototypes --------------------------------------------------*/
|
/* --- Function prototypes --------------------------------------------------*/
|
||||||
|
|
||||||
/* TODO */
|
typedef enum {
|
||||||
|
RTC_SEC, RTC_ALR, RTC_OW,
|
||||||
|
} rtcflag_t;
|
||||||
|
|
||||||
|
void rtc_awake_from_off(osc_t clock_source);
|
||||||
|
void rtc_enter_config_mode(void);
|
||||||
|
void rtc_exit_config_mode(void);
|
||||||
|
void rtc_set_alarm_time(u32 alarm_time);
|
||||||
|
void rtc_enable_alarm(void);
|
||||||
|
void rtc_disable_alarm(void);
|
||||||
|
void rtc_set_prescale_val(u32 prescale_val);
|
||||||
|
u32 rtc_get_counter_val(void);
|
||||||
|
u32 rtc_get_prescale_div_val(void);
|
||||||
|
u32 rtc_get_alarm_val(void);
|
||||||
|
void rtc_set_counter_val(u32 counter_val);
|
||||||
|
void rtc_interrupt_enable(rtcflag_t flag_val);
|
||||||
|
void rtc_interrupt_disable(rtcflag_t flag_val);
|
||||||
|
void rtc_clear_flag(rtcflag_t flag_val);
|
||||||
|
u32 rtc_check_flag(rtcflag_t flag_val);
|
||||||
|
void rtc_awake_from_standby(void);
|
||||||
|
void rtc_auto_awake(osc_t clock_source, u32 prescale_val);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -465,3 +465,11 @@ void rcc_clock_setup_in_hse_16mhz_out_72mhz(void)
|
|||||||
rcc_set_sysclk_source(SW_SYSCLKSEL_PLLCLK);
|
rcc_set_sysclk_source(SW_SYSCLKSEL_PLLCLK);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void rcc_backupdomain_reset(void)
|
||||||
|
{
|
||||||
|
/* Set the backup domain software reset. */
|
||||||
|
RCC_BDCR |= BDRST;
|
||||||
|
|
||||||
|
/* Clear the backup domain software reset. */
|
||||||
|
RCC_BDCR &= ~BDRST;
|
||||||
|
}
|
||||||
|
217
lib/rtc.c
217
lib/rtc.c
@ -2,6 +2,7 @@
|
|||||||
* This file is part of the libopenstm32 project.
|
* This file is part of the libopenstm32 project.
|
||||||
*
|
*
|
||||||
* Copyright (C) 2010 Uwe Hermann <uwe@hermann-uwe.de>
|
* Copyright (C) 2010 Uwe Hermann <uwe@hermann-uwe.de>
|
||||||
|
* Copyright (C) 2010 Lord James <lordjames@y7mail.com>
|
||||||
*
|
*
|
||||||
* This program is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
@ -19,17 +20,70 @@
|
|||||||
|
|
||||||
#include <libopenstm32/rcc.h>
|
#include <libopenstm32/rcc.h>
|
||||||
#include <libopenstm32/rtc.h>
|
#include <libopenstm32/rtc.h>
|
||||||
|
#include <libopenstm32/pwr.h>
|
||||||
|
|
||||||
void rtc_init(void)
|
void rtc_awake_from_off(osc_t clock_source)
|
||||||
{
|
{
|
||||||
|
u32 reg32;
|
||||||
|
|
||||||
/* Enable power and backup interface clocks. */
|
/* Enable power and backup interface clocks. */
|
||||||
RCC_APB1ENR |= (PWREN | BKPEN);
|
RCC_APB1ENR |= (PWREN | BKPEN);
|
||||||
|
|
||||||
/* Enable access to the backup registers and the RTC. */
|
/* Enable access to the backup registers and the RTC. */
|
||||||
/* TODO: PWR component not yet implemented in libopenstm32. */
|
PWR_CR |= PWR_CR_DBP;
|
||||||
/* PWR_CR |= PWR_CR_DBP; */
|
|
||||||
|
|
||||||
/* TODO: Wait for the RSF bit in RTC_CRL to be set by hardware? */
|
/*
|
||||||
|
* Reset the backup domain, clears everything RTC related.
|
||||||
|
* If not wanted use the rtc_awake_from_standby() function.
|
||||||
|
*/
|
||||||
|
rcc_backupdomain_reset();
|
||||||
|
|
||||||
|
switch (clock_source) {
|
||||||
|
case LSE:
|
||||||
|
/* Turn the LSE on and wait while it stabilises. */
|
||||||
|
RCC_BDCR |= LSEON;
|
||||||
|
while ((reg32 = (RCC_BDCR & LSERDY)) == 0);
|
||||||
|
|
||||||
|
/* Choose LSE as the RTC clock source. */
|
||||||
|
RCC_BDCR &= ~((1 << 8) | (1 << 9));
|
||||||
|
RCC_BDCR |= (1 << 8);
|
||||||
|
break;
|
||||||
|
case LSI:
|
||||||
|
/* Turn the LSI on and wait while it stabilises. */
|
||||||
|
RCC_CSR |= LSION;
|
||||||
|
while ((reg32 = (RCC_CSR & LSIRDY)) == 0);
|
||||||
|
|
||||||
|
/* Choose LSI as the RTC clock source. */
|
||||||
|
RCC_BDCR &= ~((1 << 8) | (1 << 9));
|
||||||
|
RCC_BDCR |= (1 << 9);
|
||||||
|
break;
|
||||||
|
case HSE:
|
||||||
|
/* Turn the HSE on and wait while it stabilises. */
|
||||||
|
RCC_CSR |= HSEON;
|
||||||
|
while ((reg32 = (RCC_CSR & HSERDY)) == 0);
|
||||||
|
|
||||||
|
/* Choose HSE as the RTC clock source. */
|
||||||
|
RCC_BDCR &= ~((1 << 8) | (1 << 9));
|
||||||
|
RCC_BDCR |= (1 << 9) | (1 << 8);
|
||||||
|
break;
|
||||||
|
case PLL:
|
||||||
|
case HSI:
|
||||||
|
/* Unusable clock source, here to prevent warnings. */
|
||||||
|
/* Turn off clock sources to RTC. */
|
||||||
|
RCC_BDCR &= ~((1 << 8) | (1 << 9));
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Enable the RTC. */
|
||||||
|
RCC_BDCR |= RTCEN;
|
||||||
|
|
||||||
|
/* Wait for the RSF bit in RTC_CRL to be set by hardware. */
|
||||||
|
RTC_CRL &= ~RTC_CRL_RSF;
|
||||||
|
while ((reg32 = (RTC_CRL & RTC_CRL_RSF)) == 0);
|
||||||
|
|
||||||
|
/* Wait for the last write operation to finish. */
|
||||||
|
/* TODO: Necessary? */
|
||||||
|
while ((reg32 = (RTC_CRL & RTC_CRL_RTOFF)) == 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
void rtc_enter_config_mode(void)
|
void rtc_enter_config_mode(void)
|
||||||
@ -45,13 +99,14 @@ void rtc_enter_config_mode(void)
|
|||||||
|
|
||||||
void rtc_exit_config_mode(void)
|
void rtc_exit_config_mode(void)
|
||||||
{
|
{
|
||||||
u32 reg32;
|
/* u32 reg32; */
|
||||||
|
|
||||||
/* Exit configuration mode. */
|
/* Exit configuration mode. */
|
||||||
RTC_CRL &= ~RTC_CRL_CNF;
|
RTC_CRL &= ~RTC_CRL_CNF;
|
||||||
|
|
||||||
/* Wait until the RTOFF bit is 1 (our RTC register write finished). */
|
/* Wait until the RTOFF bit is 1 (our RTC register write finished). */
|
||||||
while ((reg32 = (RTC_CRL & RTC_CRL_RTOFF)) == 0);
|
/* while ((reg32 = (RTC_CRL & RTC_CRL_RTOFF)) == 0); */
|
||||||
|
/* TODO: Unnecessary since we poll the bit on config entry(?) */
|
||||||
}
|
}
|
||||||
|
|
||||||
void rtc_set_alarm_time(u32 alarm_time)
|
void rtc_set_alarm_time(u32 alarm_time)
|
||||||
@ -75,3 +130,153 @@ void rtc_disable_alarm(void)
|
|||||||
RTC_CRH &= ~RTC_CRH_ALRIE;
|
RTC_CRH &= ~RTC_CRH_ALRIE;
|
||||||
rtc_exit_config_mode();
|
rtc_exit_config_mode();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void rtc_set_prescale_val(u32 prescale_val)
|
||||||
|
{
|
||||||
|
rtc_enter_config_mode();
|
||||||
|
RTC_PRLL = prescale_val & 0x0000ffff; /* PRL[15:0] */
|
||||||
|
RTC_PRLH = (prescale_val & 0x000f0000) >> 16; /* PRL[19:16] */
|
||||||
|
rtc_exit_config_mode();
|
||||||
|
}
|
||||||
|
|
||||||
|
u32 rtc_get_counter_val(void)
|
||||||
|
{
|
||||||
|
return (RTC_CNTH << 16) | RTC_CNTL;
|
||||||
|
}
|
||||||
|
|
||||||
|
u32 rtc_get_prescale_div_val(void)
|
||||||
|
{
|
||||||
|
return (RTC_DIVH << 16) | RTC_DIVL;
|
||||||
|
}
|
||||||
|
|
||||||
|
u32 rtc_get_alarm_val(void)
|
||||||
|
{
|
||||||
|
return (RTC_ALRH << 16) | RTC_ALRL;
|
||||||
|
}
|
||||||
|
|
||||||
|
void rtc_set_counter_val(u32 counter_val)
|
||||||
|
{
|
||||||
|
rtc_enter_config_mode();
|
||||||
|
RTC_PRLH = (counter_val & 0xffff0000) >> 16; /* CNT[31:16] */
|
||||||
|
RTC_PRLL = counter_val & 0x0000ffff; /* CNT[15:0] */
|
||||||
|
rtc_exit_config_mode();
|
||||||
|
}
|
||||||
|
|
||||||
|
void rtc_interrupt_enable(rtcflag_t flag_val)
|
||||||
|
{
|
||||||
|
rtc_enter_config_mode();
|
||||||
|
|
||||||
|
/* Set the correct interrupt enable. */
|
||||||
|
switch(flag_val) {
|
||||||
|
case RTC_SEC:
|
||||||
|
RTC_CRH |= RTC_CRH_SECIE;
|
||||||
|
break;
|
||||||
|
case RTC_ALR:
|
||||||
|
RTC_CRH |= RTC_CRH_ALRIE;
|
||||||
|
break;
|
||||||
|
case RTC_OW:
|
||||||
|
RTC_CRH |= RTC_CRH_OWIE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
rtc_exit_config_mode();
|
||||||
|
}
|
||||||
|
|
||||||
|
void rtc_interrupt_disable(rtcflag_t flag_val)
|
||||||
|
{
|
||||||
|
rtc_enter_config_mode();
|
||||||
|
|
||||||
|
/* Disable the correct interrupt enable. */
|
||||||
|
switch(flag_val) {
|
||||||
|
case RTC_SEC:
|
||||||
|
RTC_CRH &= ~RTC_CRH_SECIE;
|
||||||
|
break;
|
||||||
|
case RTC_ALR:
|
||||||
|
RTC_CRH &= ~RTC_CRH_ALRIE;
|
||||||
|
break;
|
||||||
|
case RTC_OW:
|
||||||
|
RTC_CRH &= ~RTC_CRH_OWIE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
rtc_exit_config_mode();
|
||||||
|
}
|
||||||
|
|
||||||
|
void rtc_clear_flag(rtcflag_t flag_val)
|
||||||
|
{
|
||||||
|
/* Configuration mode not needed. */
|
||||||
|
|
||||||
|
/* Clear the correct flag. */
|
||||||
|
switch(flag_val) {
|
||||||
|
case RTC_SEC:
|
||||||
|
RTC_CRL &= ~RTC_CRL_SECF;
|
||||||
|
break;
|
||||||
|
case RTC_ALR:
|
||||||
|
RTC_CRL &= ~RTC_CRL_ALRF;
|
||||||
|
break;
|
||||||
|
case RTC_OW:
|
||||||
|
RTC_CRL &= ~RTC_CRL_OWF;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
u32 rtc_check_flag(rtcflag_t flag_val)
|
||||||
|
{
|
||||||
|
u32 reg32;
|
||||||
|
|
||||||
|
/* Read correct flag. */
|
||||||
|
switch(flag_val) {
|
||||||
|
case RTC_SEC:
|
||||||
|
reg32 = RTC_CRL & RTC_CRL_SECF;
|
||||||
|
break;
|
||||||
|
case RTC_ALR:
|
||||||
|
reg32 = RTC_CRL & RTC_CRL_ALRF;
|
||||||
|
break;
|
||||||
|
case RTC_OW:
|
||||||
|
reg32 = RTC_CRL & RTC_CRL_OWF;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
reg32 = 0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return reg32;
|
||||||
|
}
|
||||||
|
|
||||||
|
void rtc_awake_from_standby(void)
|
||||||
|
{
|
||||||
|
u32 reg32;
|
||||||
|
|
||||||
|
/* Enable power and backup interface clocks. */
|
||||||
|
RCC_APB1ENR |= (PWREN | BKPEN);
|
||||||
|
|
||||||
|
/* Enable access to the backup registers and the RTC. */
|
||||||
|
PWR_CR |= PWR_CR_DBP;
|
||||||
|
|
||||||
|
/* Wait for the RSF bit in RTC_CRL to be set by hardware. */
|
||||||
|
RTC_CRL &= ~RTC_CRL_RSF;
|
||||||
|
while ((reg32 = (RTC_CRL & RTC_CRL_RSF)) == 0);
|
||||||
|
|
||||||
|
/* Wait for the last write operation to finish. */
|
||||||
|
/* TODO: Necessary? */
|
||||||
|
while ((reg32 = (RTC_CRL & RTC_CRL_RTOFF)) == 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
void rtc_auto_awake(osc_t clock_source, u32 prescale_val)
|
||||||
|
{
|
||||||
|
u32 reg32;
|
||||||
|
|
||||||
|
/* Enable power and backup interface clocks. */
|
||||||
|
RCC_APB1ENR |= (PWREN | BKPEN);
|
||||||
|
|
||||||
|
/* Enable access to the backup registers and the RTC. */
|
||||||
|
/* TODO: Not sure if this is necessary to just read the flag. */
|
||||||
|
PWR_CR |= PWR_CR_DBP;
|
||||||
|
|
||||||
|
if ((reg32 = RCC_BDCR & RTCEN) != 0) {
|
||||||
|
rtc_awake_from_standby();
|
||||||
|
} else {
|
||||||
|
rtc_awake_from_off(clock_source);
|
||||||
|
rtc_set_prescale_val(prescale_val);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
Loading…
x
Reference in New Issue
Block a user