aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorPiotr Esden-Tempski2013-01-06 17:58:27 -0800
committerPiotr Esden-Tempski2013-01-06 17:58:27 -0800
commit27ccf45182eb36005b7e7df2e19944ef275e2018 (patch)
tree2a4b6dc91623624e6fcdba79d013c4441cee3963
parent44e350ad20b59448b7b11f0ea7f723fe9255dcf7 (diff)
parent523943a3d205ec1d0121f9404548fd9cd4efd9f1 (diff)
Merging pull request #67 L1 support: flash, power basics, timers
Merge remote-tracking branch 'karlp/pr_l1_flash-rcc-pwr-timers'
-rw-r--r--include/libopencm3/stm32/l1/flash.h125
-rw-r--r--include/libopencm3/stm32/l1/pwr.h93
-rw-r--r--include/libopencm3/stm32/l1/rcc.h44
-rw-r--r--lib/stm32/l1/Makefile6
-rw-r--r--lib/stm32/l1/flash.c52
-rw-r--r--lib/stm32/l1/pwr_chipset.c37
-rw-r--r--lib/stm32/l1/rcc.c121
-rw-r--r--lib/stm32/timer.c109
8 files changed, 555 insertions, 32 deletions
diff --git a/include/libopencm3/stm32/l1/flash.h b/include/libopencm3/stm32/l1/flash.h
new file mode 100644
index 0000000..ed0a696
--- /dev/null
+++ b/include/libopencm3/stm32/l1/flash.h
@@ -0,0 +1,125 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ * Copyright (C) 2010 Mark Butler <mbutler@physics.otago.ac.nz>
+ * Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/*
+ * All extracted from PM0062 rev2, L15xx and L16xx Flash/EEPROM programming manual
+ */
+
+#ifndef LIBOPENCM3_FLASH_H
+#define LIBOPENCM3_FLASH_H
+
+#include <libopencm3/stm32/memorymap.h>
+#include <libopencm3/cm3/common.h>
+
+/* --- FLASH registers ----------------------------------------------------- */
+
+#define FLASH_ACR MMIO32(FLASH_MEM_INTERFACE_BASE + 0x00)
+#define FLASH_PECR MMIO32(FLASH_MEM_INTERFACE_BASE + 0x04)
+#define FLASH_PDKEYR MMIO32(FLASH_MEM_INTERFACE_BASE + 0x08)
+#define FLASH_PEKEYR MMIO32(FLASH_MEM_INTERFACE_BASE + 0x0C)
+#define FLASH_PRGKEYR MMIO32(FLASH_MEM_INTERFACE_BASE + 0x10)
+#define FLASH_OPTKEYR MMIO32(FLASH_MEM_INTERFACE_BASE + 0x14)
+#define FLASH_SR MMIO32(FLASH_MEM_INTERFACE_BASE + 0x18)
+#define FLASH_OBR MMIO32(FLASH_MEM_INTERFACE_BASE + 0x1c)
+#define FLASH_WRPR1 MMIO32(FLASH_MEM_INTERFACE_BASE + 0x20)
+#define FLASH_WRPR2 MMIO32(FLASH_MEM_INTERFACE_BASE + 0x80)
+#define FLASH_WRPR3 MMIO32(FLASH_MEM_INTERFACE_BASE + 0x84)
+
+/* --- FLASH_ACR values ---------------------------------------------------- */
+
+#define FLASH_RUNPD (1 << 4)
+#define FLASH_SLEEPPD (1 << 3)
+#define FLASH_ACC64 (1 << 2)
+#define FLASH_PRFTEN (1 << 1)
+#define FLASH_LATENCY_0WS 0x00
+#define FLASH_LATENCY_1WS 0x01
+
+/* --- FLASH_PECR values. Program/erase control register */
+#define FLASH_OBL_LAUNCH (1 << 18)
+#define FLASH_ERRIE (1 << 17)
+#define FLASH_EOPIE (1 << 16)
+#define FLASH_PARALLBANK (1 << 15)
+#define FLASH_FPRG (1 << 10)
+#define FLASH_ERASE (1 << 9)
+#define FLASH_FTDW (1 << 8)
+#define FLASH_FTDW (1 << 8)
+#define FLASH_DATA (1 << 4)
+#define FLASH_PROG (1 << 3)
+#define FLASH_OPTLOCK (1 << 2)
+#define FLASH_PRGLOCK (1 << 1)
+#define FLASH_PELOCK (1 << 0)
+
+/* Power down key register (FLASH_PDKEYR) */
+#define FLASH_PDKEY1 ((u32)0x04152637)
+#define FLASH_PDKEY2 ((u32)0xFAFBFCFD)
+
+/* Program/erase key register (FLASH_PEKEYR) */
+#define FLASH_PEKEY1 ((u32)0x89ABCDEF)
+#define FLASH_PEKEY2 ((u32)0x02030405)
+
+/* Program memory key register (FLASH_PRGKEYR) */
+#define FLASH_PRGKEY1 ((u32)0x8C9DAEBF)
+#define FLASH_PRGKEY2 ((u32)0x13141516)
+
+/* Option byte key register (FLASH_OPTKEYR) */
+#define FLASH_OPTKEY1 ((u32)0xFBEAD9C8)
+#define FLASH_OPTKEY2 ((u32)0x24252627)
+
+
+/* --- FLASH_SR values ----------------------------------------------------- */
+#define FLASH_OPTVERRUSR (1 << 12)
+#define FLASH_OPTVERR (1 << 11)
+#define FLASH_SIZEERR (1 << 10)
+#define FLASH_PGAERR (1 << 9)
+#define FLASH_WRPERR (1 << 8)
+#define FLASH_READY (1 << 3)
+#define FLASH_ENDHV (1 << 2)
+#define FLASH_EOP (1 << 1)
+#define FLASH_BSY (1 << 0)
+
+/* --- FLASH_OBR values ----------------------------------------------------- */
+#define FLASH_BFB2 (1 << 23)
+#define FLASH_NRST_STDBY (1 << 22)
+#define FLASH_NRST_STOP (1 << 21)
+#define FLASH_IWDG_SW (1 << 20)
+#define FLASH_BOR_OFF (0x0 << 16)
+#define FLASH_BOR_LEVEL_1 (0x8 << 16)
+#define FLASH_BOR_LEVEL_2 (0x9 << 16)
+#define FLASH_BOR_LEVEL_3 (0xa << 16)
+#define FLASH_BOR_LEVEL_4 (0xb << 16)
+#define FLASH_BOR_LEVEL_5 (0xc << 16)
+#define FLASH_RDPRT_LEVEL_0 (0xaa)
+#define FLASH_RDPRT_LEVEL_1 (0x00)
+#define FLASH_RDPRT_LEVEL_2 (0xcc)
+
+/* --- Function prototypes ------------------------------------------------- */
+
+BEGIN_DECLS
+
+void flash_64bit_enable(void);
+void flash_64bit_disable(void);
+void flash_prefetch_enable(void);
+void flash_prefetch_disable(void);
+void flash_set_ws(u32 ws);
+
+END_DECLS
+
+#endif
diff --git a/include/libopencm3/stm32/l1/pwr.h b/include/libopencm3/stm32/l1/pwr.h
new file mode 100644
index 0000000..309b464
--- /dev/null
+++ b/include/libopencm3/stm32/l1/pwr.h
@@ -0,0 +1,93 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2011 Stephen Caudle <scaudle@doceme.com>
+ * Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#ifndef LIBOPENCM3_PWR_L1_H
+#define LIBOPENCM3_PWR_L1_H
+
+#include <libopencm3/stm32/pwr.h>
+
+/*
+ * This file extends the common STM32 version with definitions only
+ * applicable to the STM32L1 series of devices.
+ */
+
+/* --- PWR_CR values ------------------------------------------------------- */
+
+/* Bits [31:15]: Reserved */
+
+/* LPRUN: Low power run mode */
+#define PWR_CR_LPRUN (1 << 14)
+
+/* VOS[12:11]: Regulator voltage scaling output selection */
+#define PWR_CR_VOS_LSB 11
+/** @defgroup pwr_vos Voltage Scaling Output level selection
+@ingroup STM32F_pwr_defines
+
+@{*/
+#define PWR_CR_VOS_RANGE1 (0x1 << PWR_CR_VOS_LSB)
+#define PWR_CR_VOS_RANGE2 (0x2 << PWR_CR_VOS_LSB)
+#define PWR_CR_VOS_RANGE3 (0x3 << PWR_CR_VOS_LSB)
+/**@}*/
+#define PWR_CR_VOS_MASK (0x3 << PWR_CR_VOS_LSB)
+
+/* FWU: Fast wakeup */
+#define PWR_CR_FWU (1 << 10)
+
+/* ULP: Ultralow power mode */
+#define PWR_CR_ULP (1 << 9)
+
+/* --- PWR_CSR values ------------------------------------------------------- */
+
+/* Bits [31:11]: Reserved */
+/* EWUP3: Enable WKUP3 pin */
+#define PWR_CSR_EWUP3 (1 << 10)
+
+/* EWUP2: Enable WKUP2 pin */
+#define PWR_CSR_EWUP2 (1 << 9)
+
+/* EWUP1: Enable WKUP1 pin */
+#define PWR_CSR_EWUP1 PWR_CSR_EWUP
+
+/* REGLPF : Regulator LP flag */
+#define PWR_CSR_REGLPF (1 << 5)
+
+/* VOSF: Voltage Scaling select flag */
+#define PWR_CSR_VOSF (1 << 4)
+
+/* VREFINTRDYF: Internal voltage reference (VREFINT) ready flag */
+#define PWR_CSR_VREFINTRDYF (1 << 3)
+
+
+
+/* --- Function prototypes ------------------------------------------------- */
+
+typedef enum {
+ RANGE1,
+ RANGE2,
+ RANGE3,
+} vos_scale_t;
+
+BEGIN_DECLS
+
+void pwr_set_vos_scale(vos_scale_t scale);
+
+END_DECLS
+
+#endif
diff --git a/include/libopencm3/stm32/l1/rcc.h b/include/libopencm3/stm32/l1/rcc.h
index d888d7c..21b073b 100644
--- a/include/libopencm3/stm32/l1/rcc.h
+++ b/include/libopencm3/stm32/l1/rcc.h
@@ -46,6 +46,7 @@ LGPL License Terms @ref lgpl_license
#include <libopencm3/stm32/memorymap.h>
#include <libopencm3/cm3/common.h>
+#include <libopencm3/stm32/l1/pwr.h>
/* --- RCC registers ------------------------------------------------------- */
@@ -110,6 +111,8 @@ LGPL License Terms @ref lgpl_license
#define RCC_CFGR_PLLDIV_DIV2 0x1
#define RCC_CFGR_PLLDIV_DIV3 0x2
#define RCC_CFGR_PLLDIV_DIV4 0x3
+#define RCC_CFGR_PLLDIV_SHIFT 22
+#define RCC_CFGR_PLLDIV_MASK 0x3
/* PLLMUL: PLL multiplication factor */
#define RCC_CFGR_PLLMUL_MUL3 0x0
@@ -121,6 +124,8 @@ LGPL License Terms @ref lgpl_license
#define RCC_CFGR_PLLMUL_MUL24 0x6
#define RCC_CFGR_PLLMUL_MUL32 0x7
#define RCC_CFGR_PLLMUL_MUL48 0x8
+#define RCC_CFGR_PLLMUL_SHIFT 18
+#define RCC_CFGR_PLLMUL_MASK 0xf
/* PLLSRC: PLL entry clock source */
#define RCC_CFGR_PLLSRC_HSI_CLK 0x0
@@ -231,6 +236,7 @@ LGPL License Terms @ref lgpl_license
#define RCC_APB1RSTR_LCDRST (1 << 9)
#define RCC_APB1RSTR_TIM7RST (1 << 5)
#define RCC_APB1RSTR_TIM6RST (1 << 4)
+#define RCC_APB1RSTR_TIM5RST (1 << 3)
#define RCC_APB1RSTR_TIM4RST (1 << 2)
#define RCC_APB1RSTR_TIM3RST (1 << 1)
#define RCC_APB1RSTR_TIM2RST (1 << 0)
@@ -348,6 +354,28 @@ LGPL License Terms @ref lgpl_license
#define RCC_CSR_LSIRDY (1 << 1)
#define RCC_CSR_LSION (1 << 0)
+typedef struct {
+ uint8_t pll_mul;
+ uint16_t pll_div;
+ uint8_t pll_source;
+ uint32_t flash_config;
+ uint8_t hpre;
+ uint8_t ppre1;
+ uint8_t ppre2;
+ vos_scale_t voltage_scale;
+ uint32_t apb1_frequency;
+ uint32_t apb2_frequency;
+} clock_scale_t;
+
+typedef enum {
+ CLOCK_VRANGE1_HSI_PLL_24MHZ,
+ CLOCK_VRANGE1_HSI_PLL_32MHZ,
+ CLOCK_VRANGE1_HSI_RAW_16MHZ,
+ CLOCK_VRANGE1_END
+} clock_volt_range1_t;
+
+extern const clock_scale_t clock_vrange1_config[CLOCK_VRANGE1_END];
+
/* --- Variable definitions ------------------------------------------------ */
extern u32 rcc_ppre1_frequency;
@@ -377,26 +405,16 @@ void rcc_peripheral_disable_clock(volatile u32 *reg, u32 en);
void rcc_peripheral_reset(volatile u32 *reg, u32 reset);
void rcc_peripheral_clear_reset(volatile u32 *reg, u32 clear_reset);
void rcc_set_sysclk_source(u32 clk);
-void rcc_set_pll_multiplication_factor(u32 mul);
+void rcc_set_pll_configuration(u32 source, u32 multiplier, u32 divisor);
void rcc_set_pll_source(u32 pllsrc);
-void rcc_set_pllxtpre(u32 pllxtpre);
void rcc_set_adcpre(u32 adcpre);
void rcc_set_ppre2(u32 ppre2);
void rcc_set_ppre1(u32 ppre1);
void rcc_set_hpre(u32 hpre);
void rcc_set_usbpre(u32 usbpre);
u32 rcc_get_system_clock_source(int i);
-void rcc_clock_setup_in_hsi_out_64mhz(void);
-void rcc_clock_setup_in_hsi_out_48mhz(void);
-
-/**
- * Maximum speed possible for F100 (Value Line) on HSI
- */
-void rcc_clock_setup_in_hsi_out_24mhz(void);
-void rcc_clock_setup_in_hse_8mhz_out_24mhz(void);
-void rcc_clock_setup_in_hse_8mhz_out_72mhz(void);
-void rcc_clock_setup_in_hse_12mhz_out_72mhz(void);
-void rcc_clock_setup_in_hse_16mhz_out_72mhz(void);
+void rcc_clock_setup_hsi(const clock_scale_t *clock);
+void rcc_clock_setup_pll(const clock_scale_t *clock);
void rcc_backupdomain_reset(void);
/**@}*/
diff --git a/lib/stm32/l1/Makefile b/lib/stm32/l1/Makefile
index 7f3e157..a3c8856 100644
--- a/lib/stm32/l1/Makefile
+++ b/lib/stm32/l1/Makefile
@@ -28,8 +28,10 @@ CFLAGS = -Os -g -Wall -Wextra -I../../../include -fno-common \
-ffunction-sections -fdata-sections -MD -DSTM32L1
# ARFLAGS = rcsv
ARFLAGS = rcs
-OBJS = rcc.o gpio.o desig.o crc.o usart.o exti2.o \
- gpio_common_all.o gpio_common_f24.o
+OBJS = rcc.o gpio.o desig.o crc.o usart.o exti2.o
+OBJS += flash.o gpio_common_all.o gpio_common_f24.o
+OBJS += pwr_chipset.o # TODO, get pwr.o to fix f2/f4 first... pwr.o
+OBJS += timer.o
VPATH += ../../usb:../:../../cm3:../common
diff --git a/lib/stm32/l1/flash.c b/lib/stm32/l1/flash.c
new file mode 100644
index 0000000..06e8a59
--- /dev/null
+++ b/lib/stm32/l1/flash.c
@@ -0,0 +1,52 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ * Copyright (C) 2010 Mark Butler <mbutler@physics.otago.ac.nz>
+ * Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopencm3/stm32/l1/flash.h>
+
+void flash_64bit_enable(void)
+{
+ FLASH_ACR |= FLASH_ACC64;
+}
+
+void flash_64bit_disable(void)
+{
+ FLASH_ACR &= ~FLASH_ACC64;
+}
+
+void flash_prefetch_enable(void)
+{
+ FLASH_ACR |= FLASH_PRFTEN;
+}
+
+void flash_prefetch_disable(void)
+{
+ FLASH_ACR &= ~FLASH_PRFTEN;
+}
+
+void flash_set_ws(u32 ws)
+{
+ u32 reg32;
+
+ reg32 = FLASH_ACR;
+ reg32 &= ~(1 << 0);
+ reg32 |= ws;
+ FLASH_ACR = reg32;
+} \ No newline at end of file
diff --git a/lib/stm32/l1/pwr_chipset.c b/lib/stm32/l1/pwr_chipset.c
new file mode 100644
index 0000000..9f4f599
--- /dev/null
+++ b/lib/stm32/l1/pwr_chipset.c
@@ -0,0 +1,37 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopencm3/stm32/l1/pwr.h>
+
+void pwr_set_vos_scale(vos_scale_t scale)
+{
+ PWR_CR &= ~(PWR_CR_VOS_MASK);
+ switch (scale) {
+ case RANGE1:
+ PWR_CR |= PWR_CR_VOS_RANGE1;
+ break;
+ case RANGE2:
+ PWR_CR |= PWR_CR_VOS_RANGE2;
+ break;
+ case RANGE3:
+ PWR_CR |= PWR_CR_VOS_RANGE3;
+ break;
+ }
+}
+
diff --git a/lib/stm32/l1/rcc.c b/lib/stm32/l1/rcc.c
index a023622..bbba9a9 100644
--- a/lib/stm32/l1/rcc.c
+++ b/lib/stm32/l1/rcc.c
@@ -22,11 +22,50 @@
*/
#include <libopencm3/stm32/l1/rcc.h>
+#include <libopencm3/stm32/l1/flash.h>
+#include <libopencm3/stm32/l1/pwr.h>
/* Set the default ppre1 and ppre2 peripheral clock frequencies after reset. */
u32 rcc_ppre1_frequency = 2097000;
u32 rcc_ppre2_frequency = 2097000;
+const clock_scale_t clock_vrange1_config[CLOCK_VRANGE1_END] =
+{
+ { /* 24MHz PLL from HSI */
+ .pll_source = RCC_CFGR_PLLSRC_HSI_CLK,
+ .pll_mul = RCC_CFGR_PLLMUL_MUL3,
+ .pll_div = RCC_CFGR_PLLDIV_DIV2,
+ .hpre = RCC_CFGR_HPRE_SYSCLK_NODIV,
+ .ppre1 = RCC_CFGR_PPRE1_HCLK_NODIV,
+ .ppre2 = RCC_CFGR_PPRE2_HCLK_NODIV,
+ .voltage_scale = RANGE1,
+ .flash_config = FLASH_LATENCY_1WS,
+ .apb1_frequency = 24000000,
+ .apb2_frequency = 24000000,
+ },
+ { /* 32MHz PLL from HSI */
+ .pll_source = RCC_CFGR_PLLSRC_HSI_CLK,
+ .pll_mul = RCC_CFGR_PLLMUL_MUL6,
+ .pll_div = RCC_CFGR_PLLDIV_DIV3,
+ .hpre = RCC_CFGR_HPRE_SYSCLK_NODIV,
+ .ppre1 = RCC_CFGR_PPRE1_HCLK_NODIV,
+ .ppre2 = RCC_CFGR_PPRE2_HCLK_NODIV,
+ .voltage_scale = RANGE1,
+ .flash_config = FLASH_LATENCY_1WS,
+ .apb1_frequency = 32000000,
+ .apb2_frequency = 32000000,
+ },
+ { /* 16MHz HSI raw */
+ .hpre = RCC_CFGR_HPRE_SYSCLK_NODIV,
+ .ppre1 = RCC_CFGR_PPRE1_HCLK_NODIV,
+ .ppre2 = RCC_CFGR_PPRE2_HCLK_NODIV,
+ .voltage_scale = RANGE1,
+ .flash_config = FLASH_LATENCY_0WS,
+ .apb1_frequency = 16000000,
+ .apb2_frequency = 16000000,
+ },
+};
+
void rcc_osc_ready_int_clear(osc_t osc)
{
switch (osc) {
@@ -304,6 +343,20 @@ void rcc_set_sysclk_source(u32 clk)
RCC_CFGR = (reg32 | clk);
}
+void rcc_set_pll_configuration(u32 source, u32 multiplier, u32 divisor)
+{
+ u32 reg32;
+
+ reg32 = RCC_CFGR;
+ reg32 &= ~(RCC_CFGR_PLLDIV_MASK << RCC_CFGR_PLLDIV_SHIFT);
+ reg32 &= ~(RCC_CFGR_PLLMUL_MASK << RCC_CFGR_PLLMUL_SHIFT);
+ reg32 &= ~(1 << 16);
+ reg32 |= (source << 16);
+ reg32 |= (multiplier << RCC_CFGR_PLLMUL_SHIFT);
+ reg32 |= (divisor << RCC_CFGR_PLLDIV_SHIFT);
+ RCC_CFGR = reg32;
+}
+
void rcc_set_pll_source(u32 pllsrc)
{
u32 reg32;
@@ -355,3 +408,71 @@ u32 rcc_system_clock_source(void)
return ((RCC_CFGR & 0x000c) >> 2);
}
+void rcc_clock_setup_hsi(const clock_scale_t *clock)
+{
+ /* Enable internal high-speed oscillator. */
+ rcc_osc_on(HSI);
+ rcc_wait_for_osc_ready(HSI);
+
+ /* Select HSI as SYSCLK source. */
+ rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_HSICLK);
+
+ /*
+ * Set prescalers for AHB, ADC, ABP1, ABP2.
+ * Do this before touching the PLL (TODO: why?).
+ */
+ rcc_set_hpre(clock->hpre);
+ rcc_set_ppre1(clock->ppre1);
+ rcc_set_ppre2(clock->ppre2);
+
+ pwr_set_vos_scale(clock->voltage_scale);
+
+ // I guess this should be in the settings?
+ flash_64bit_enable();
+ flash_prefetch_enable();
+ /* Configure flash settings. */
+ flash_set_ws(clock->flash_config);
+
+ /* Set the peripheral clock frequencies used. */
+ rcc_ppre1_frequency = clock->apb1_frequency;
+ rcc_ppre2_frequency = clock->apb2_frequency;
+}
+
+void rcc_clock_setup_pll(const clock_scale_t *clock)
+{
+ /* Enable internal high-speed oscillator. */
+ rcc_osc_on(HSI);
+ rcc_wait_for_osc_ready(HSI);
+
+ /* Select HSI as SYSCLK source. */
+ rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_HSICLK);
+
+ /*
+ * Set prescalers for AHB, ADC, ABP1, ABP2.
+ * Do this before touching the PLL (TODO: why?).
+ */
+ rcc_set_hpre(clock->hpre);
+ rcc_set_ppre1(clock->ppre1);
+ rcc_set_ppre2(clock->ppre2);
+
+ pwr_set_vos_scale(clock->voltage_scale);
+
+ // I guess this should be in the settings?
+ flash_64bit_enable();
+ flash_prefetch_enable();
+ /* Configure flash settings. */
+ flash_set_ws(clock->flash_config);
+
+ rcc_set_pll_configuration(clock->pll_source, clock->pll_mul, clock->pll_div);
+
+ /* Enable PLL oscillator and wait for it to stabilize. */
+ rcc_osc_on(PLL);
+ rcc_wait_for_osc_ready(PLL);
+
+ /* Select PLL as SYSCLK source. */
+ rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_PLLCLK);
+
+ /* Set the peripheral clock frequencies used. */
+ rcc_ppre1_frequency = clock->apb1_frequency;
+ rcc_ppre2_frequency = clock->apb2_frequency;
+}
diff --git a/lib/stm32/timer.c b/lib/stm32/timer.c
index a5cf99d..d3c26e8 100644
--- a/lib/stm32/timer.c
+++ b/lib/stm32/timer.c
@@ -99,13 +99,18 @@ push-pull outputs where the PWM output will appear.
#include <libopencm3/stm32/timer.h>
#if defined(STM32F1)
+#define ADVANCED_TIMERS (defined (TIM1_BASE) || defined(TIM8_BASE))
# include <libopencm3/stm32/f1/rcc.h>
#elif defined(STM32F2)
+#define ADVANCED_TIMERS (defined (TIM1_BASE) || defined(TIM8_BASE))
# include <libopencm3/stm32/f2/timer.h>
# include <libopencm3/stm32/f2/rcc.h>
#elif defined(STM32F4)
+#define ADVANCED_TIMERS (defined (TIM1_BASE) || defined(TIM8_BASE))
# include <libopencm3/stm32/f4/timer.h>
# include <libopencm3/stm32/f4/rcc.h>
+#elif defined(STM32L1)
+# include <libopencm3/stm32/l1/rcc.h>
#else
# error "stm32 family not defined."
#endif
@@ -124,10 +129,12 @@ system.
void timer_reset(u32 timer_peripheral)
{
switch (timer_peripheral) {
+#if defined(TIM1_BASE)
case TIM1:
rcc_peripheral_reset(&RCC_APB2RSTR, RCC_APB2RSTR_TIM1RST);
rcc_peripheral_clear_reset(&RCC_APB2RSTR, RCC_APB2RSTR_TIM1RST);
break;
+#endif
case TIM2:
rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1RSTR_TIM2RST);
rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1RSTR_TIM2RST);
@@ -140,10 +147,12 @@ void timer_reset(u32 timer_peripheral)
rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1RSTR_TIM4RST);
rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1RSTR_TIM4RST);
break;
+#if defined(TIM5_BASE)
case TIM5:
rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1RSTR_TIM5RST);
rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1RSTR_TIM5RST);
break;
+#endif
case TIM6:
rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1RSTR_TIM6RST);
rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1RSTR_TIM6RST);
@@ -152,10 +161,12 @@ void timer_reset(u32 timer_peripheral)
rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1RSTR_TIM7RST);
rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1RSTR_TIM7RST);
break;
+#if defined(TIM8_BASE)
case TIM8:
rcc_peripheral_reset(&RCC_APB2RSTR, RCC_APB2RSTR_TIM8RST);
rcc_peripheral_clear_reset(&RCC_APB2RSTR, RCC_APB2RSTR_TIM8RST);
break;
+#endif
/* These timers are not supported in libopencm3 yet */
/*
case TIM9:
@@ -230,8 +241,10 @@ bool timer_interrupt_source(u32 timer_peripheral, u32 flag)
if (((TIM_SR(timer_peripheral) & TIM_DIER(timer_peripheral) & flag) == 0) ||
(flag > TIM_SR_BIF)) return false;
/* Only an interrupt source for advanced timers */
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((flag == TIM_SR_BIF) || (flag == TIM_SR_COMIF))
return ((timer_peripheral == TIM1) || (timer_peripheral == TIM8));
+#endif
return true;
}
@@ -416,7 +429,7 @@ void timer_continuous_mode(u32 timer_peripheral)
/*---------------------------------------------------------------------------*/
/** @brief Set the Timer to Generate Update IRQ or DMA on any Event.
-The events which will generate an interrupt or DMA request can be
+The events which will generate an interrupt or DMA request can be
@li a counter underflow/overflow,
@li a forced update,
@li an event from the slave mode controller.
@@ -504,8 +517,10 @@ If several settings are to be made, use the logical OR of the output control val
void timer_set_output_idle_state(u32 timer_peripheral, u32 outputs)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_CR2(timer_peripheral) |= outputs & TIM_CR2_OIS_MASK;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -523,8 +538,10 @@ This determines the value of the timer output compare when it enters idle state.
void timer_reset_output_idle_state(u32 timer_peripheral, u32 outputs)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_CR2(timer_peripheral) &= ~(outputs & TIM_CR2_OIS_MASK);
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -611,8 +628,10 @@ outputs.
void timer_enable_compare_control_update_on_trigger(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
- TIM_CR2(timer_peripheral) |= TIM_CR2_CCUS;
+ TIM_CR2(timer_peripheral) |= TIM_CR2_CCUS;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -630,8 +649,10 @@ outputs.
void timer_disable_compare_control_update_on_trigger(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
- TIM_CR2(timer_peripheral) &= ~TIM_CR2_CCUS;
+ TIM_CR2(timer_peripheral) &= ~TIM_CR2_CCUS;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -648,8 +669,10 @@ outputs.
void timer_enable_preload_complementry_enable_bits(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
- TIM_CR2(timer_peripheral) |= TIM_CR2_CCPC;
+ TIM_CR2(timer_peripheral) |= TIM_CR2_CCPC;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -665,8 +688,10 @@ outputs.
void timer_disable_preload_complementry_enable_bits(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
- TIM_CR2(timer_peripheral) &= ~TIM_CR2_CCPC;
+ TIM_CR2(timer_peripheral) &= ~TIM_CR2_CCPC;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -697,8 +722,10 @@ count cycles have been completed.
void timer_set_repetition_counter(u32 timer_peripheral, u32 value)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_RCR(timer_peripheral) = value;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1019,7 +1046,7 @@ void timer_set_oc_mode(u32 timer_peripheral, enum tim_oc_id oc_id,
/** @brief Timer Enable the Output Compare Preload Register
@param[in] timer_peripheral Unsigned int32. Timer register address base @ref tim_reg_base
-@param[in] oc_id enum ::tim_oc_id OC channel designators
+@param[in] oc_id enum ::tim_oc_id OC channel designators
TIM_OCx where x=1..4, TIM_OCxN where x=1..3 (no action taken)
*/
@@ -1050,7 +1077,7 @@ void timer_enable_oc_preload(u32 timer_peripheral, enum tim_oc_id oc_id)
/** @brief Timer Disable the Output Compare Preload Register
@param[in] timer_peripheral Unsigned int32. Timer register address base @ref tim_reg_base
-@param[in] oc_id enum ::tim_oc_id OC channel designators
+@param[in] oc_id enum ::tim_oc_id OC channel designators
TIM_OCx where x=1..4, TIM_OCxN where x=1..3 (no action)
*/
@@ -1083,7 +1110,7 @@ void timer_disable_oc_preload(u32 timer_peripheral, enum tim_oc_id oc_id)
The polarity of the channel output is set active high.
@param[in] timer_peripheral Unsigned int32. Timer register address base @ref tim_reg_base
-@param[in] oc_id enum ::tim_oc_id OC channel designators
+@param[in] oc_id enum ::tim_oc_id OC channel designators
TIM_OCx where x=1..4, TIM_OCxN where x=1..3 (only for advanced timers 1 and 8)
*/
@@ -1110,8 +1137,12 @@ void timer_set_oc_polarity_high(u32 timer_peripheral, enum tim_oc_id oc_id)
}
/* Acting for TIM1 and TIM8 only from here onwards. */
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral != TIM1) && (timer_peripheral != TIM8))
return;
+#else
+ return;
+#endif
switch (oc_id) {
case TIM_OC1N:
@@ -1138,7 +1169,7 @@ void timer_set_oc_polarity_high(u32 timer_peripheral, enum tim_oc_id oc_id)
The polarity of the channel output is set active low.
@param[in] timer_peripheral Unsigned int32. Timer register address base @ref tim_reg_base
-@param[in] oc_id enum ::tim_oc_id OC channel designators
+@param[in] oc_id enum ::tim_oc_id OC channel designators
TIM_OCx where x=1..4, TIM_OCxN where x=1..3 (only for advanced timers 1 and 8)
*/
@@ -1165,8 +1196,12 @@ void timer_set_oc_polarity_low(u32 timer_peripheral, enum tim_oc_id oc_id)
}
/* Acting for TIM1 and TIM8 only from here onwards. */
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral != TIM1) && (timer_peripheral != TIM8))
return;
+#else
+ return;
+#endif
switch (oc_id) {
case TIM_OC1N:
@@ -1193,7 +1228,7 @@ void timer_set_oc_polarity_low(u32 timer_peripheral, enum tim_oc_id oc_id)
The channel output compare functionality is enabled.
@param[in] timer_peripheral Unsigned int32. Timer register address base @ref tim_reg_base
-@param[in] oc_id enum ::tim_oc_id OC channel designators
+@param[in] oc_id enum ::tim_oc_id OC channel designators
TIM_OCx where x=1..4, TIM_OCxN where x=1..3 (only for advanced timers 1 and 8)
*/
@@ -1220,8 +1255,12 @@ void timer_enable_oc_output(u32 timer_peripheral, enum tim_oc_id oc_id)
}
/* Acting for TIM1 and TIM8 only from here onwards. */
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral != TIM1) && (timer_peripheral != TIM8))
return;
+#else
+ return;
+#endif
switch (oc_id) {
case TIM_OC1N:
@@ -1248,7 +1287,7 @@ void timer_enable_oc_output(u32 timer_peripheral, enum tim_oc_id oc_id)
The channel output compare functionality is disabled.
@param[in] timer_peripheral Unsigned int32. Timer register address base @ref tim_reg_base
-@param[in] oc_id enum ::tim_oc_id OC channel designators
+@param[in] oc_id enum ::tim_oc_id OC channel designators
TIM_OCx where x=1..4, TIM_OCxN where x=1..3 (only for advanced timers 1 and 8)
*/
@@ -1275,8 +1314,12 @@ void timer_disable_oc_output(u32 timer_peripheral, enum tim_oc_id oc_id)
}
/* Acting for TIM1 and TIM8 only from here onwards. */
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral != TIM1) && (timer_peripheral != TIM8))
return;
+#else
+ return;
+#endif
switch (oc_id) {
case TIM_OC1N:
@@ -1306,12 +1349,13 @@ void timer_disable_oc_output(u32 timer_peripheral, enum tim_oc_id oc_id)
@note This setting is only valid for the advanced timers.
@param[in] timer_peripheral Unsigned int32. Timer register address base @ref tim_reg_base
-@param[in] oc_id enum ::tim_oc_id OC channel designators
+@param[in] oc_id enum ::tim_oc_id OC channel designators
TIM_OCx where x=1..4, TIM_OCxN where x=1..3 (only for advanced timers 1 and 8)
*/
void timer_set_oc_idle_state_set(u32 timer_peripheral, enum tim_oc_id oc_id)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
/* Acting for TIM1 and TIM8 only. */
if ((timer_peripheral != TIM1) && (timer_peripheral != TIM8))
return;
@@ -1339,6 +1383,7 @@ void timer_set_oc_idle_state_set(u32 timer_peripheral, enum tim_oc_id oc_id)
TIM_CR2(timer_peripheral) |= TIM_CR2_OIS4;
break;
}
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1350,12 +1395,13 @@ void timer_set_oc_idle_state_set(u32 timer_peripheral, enum tim_oc_id oc_id)
@note This setting is only valid for the advanced timers.
@param[in] timer_peripheral Unsigned int32. Timer register address base @ref tim_reg_base
-@param[in] oc_id enum ::tim_oc_id OC channel designators
+@param[in] oc_id enum ::tim_oc_id OC channel designators
TIM_OCx where x=1..4, TIM_OCxN where x=1..3 (only for advanced timers 1 and 8)
*/
void timer_set_oc_idle_state_unset(u32 timer_peripheral, enum tim_oc_id oc_id)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
/* Acting for TIM1 and TIM8 only. */
if ((timer_peripheral != TIM1) && (timer_peripheral != TIM8))
return;
@@ -1383,6 +1429,7 @@ void timer_set_oc_idle_state_unset(u32 timer_peripheral, enum tim_oc_id oc_id)
TIM_CR2(timer_peripheral) &= ~TIM_CR2_OIS4;
break;
}
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1393,7 +1440,7 @@ to the compare register.
@param[in] timer_peripheral Unsigned int32. Timer register address base @ref tim_reg_base
(TIM9 .. TIM14 not yet supported here).
-@param[in] oc_id enum ::tim_oc_id OC channel designators
+@param[in] oc_id enum ::tim_oc_id OC channel designators
TIM_OCx where x=1..4, TIM_OCxN where x=1..3 (no action taken)
@param[in] value Unsigned int32. Compare value.
*/
@@ -1438,8 +1485,10 @@ timer <b>even if break or deadtime features are not being used</b>.
void timer_enable_break_main_output(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) |= TIM_BDTR_MOE;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1455,8 +1504,10 @@ the Master Output Enable in the Break and Deadtime Register.
void timer_disable_break_main_output(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) &= ~TIM_BDTR_MOE;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1464,7 +1515,7 @@ void timer_disable_break_main_output(u32 timer_peripheral)
Enables the automatic output feature of the Break function of an advanced
timer so that the output is re-enabled at the next update event following a
-break event.
+break event.
@note This setting is only valid for the advanced timers.
@@ -1473,8 +1524,10 @@ break event.
void timer_enable_break_automatic_output(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) |= TIM_BDTR_AOE;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1482,7 +1535,7 @@ void timer_enable_break_automatic_output(u32 timer_peripheral)
Disables the automatic output feature of the Break function of an advanced
timer so that the output is re-enabled at the next update event following a
-break event.
+break event.
@note This setting is only valid for the advanced timers.
@@ -1491,8 +1544,10 @@ break event.
void timer_disable_break_automatic_output(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) &= ~TIM_BDTR_AOE;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1507,8 +1562,10 @@ Sets the break function to activate when the break input becomes high.
void timer_set_break_polarity_high(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) |= TIM_BDTR_BKP;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1523,8 +1580,10 @@ Sets the break function to activate when the break input becomes low.
void timer_set_break_polarity_low(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) &= ~TIM_BDTR_BKP;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1539,8 +1598,10 @@ Enables the break function of an advanced timer.
void timer_enable_break(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) |= TIM_BDTR_BKE;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1555,8 +1616,10 @@ Disables the break function of an advanced timer.
void timer_disable_break(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) &= ~TIM_BDTR_BKE;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1575,8 +1638,10 @@ inactive level as defined by the output polarity.
void timer_set_enabled_off_state_in_run_mode(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) |= TIM_BDTR_OSSR;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1594,8 +1659,10 @@ disabled, the output is also disabled.
void timer_set_disabled_off_state_in_run_mode(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) &= ~TIM_BDTR_OSSR;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1612,8 +1679,10 @@ inactive level as defined by the output polarity.
void timer_set_enabled_off_state_in_idle_mode(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) |= TIM_BDTR_OSSI;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1629,8 +1698,10 @@ timer. When the master output is disabled the output is also disabled.
void timer_set_disabled_off_state_in_idle_mode(u32 timer_peripheral)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) &= ~TIM_BDTR_OSSI;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1648,8 +1719,10 @@ timer reset has occurred.
void timer_set_break_lock(u32 timer_peripheral, u32 lock)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) |= lock;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1672,8 +1745,10 @@ number of DTSC cycles:
void timer_set_deadtime(u32 timer_peripheral, u32 deadtime)
{
+#if (defined(ADVANCED_TIMERS) && (ADVANCED_TIMERS))
if ((timer_peripheral == TIM1) || (timer_peripheral == TIM8))
TIM_BDTR(timer_peripheral) |= deadtime;
+#endif
}
/*---------------------------------------------------------------------------*/
@@ -1842,7 +1917,7 @@ void timer_ic_set_input(u32 timer_peripheral, enum tim_ic_id ic, enum tim_ic_inp
/* Input select bits are flipped for these combinations */
in ^= 3;
}
-
+
switch (ic) {
case TIM_IC1:
TIM_CCMR1(timer_peripheral) &= ~TIM_CCMR1_CC1S_MASK;