aboutsummaryrefslogtreecommitdiffstats
path: root/libmaple/stm32f1
diff options
context:
space:
mode:
Diffstat (limited to 'libmaple/stm32f1')
-rw-r--r--libmaple/stm32f1/adc.c115
-rw-r--r--libmaple/stm32f1/bkp.c129
-rw-r--r--libmaple/stm32f1/dma.c413
-rw-r--r--libmaple/stm32f1/exti.c32
-rw-r--r--libmaple/stm32f1/fsmc.c95
-rw-r--r--libmaple/stm32f1/gpio.c166
-rw-r--r--libmaple/stm32f1/i2c.c129
-rw-r--r--libmaple/stm32f1/include/series/adc.h253
-rw-r--r--libmaple/stm32f1/include/series/dac.h71
-rw-r--r--libmaple/stm32f1/include/series/dma.h575
-rw-r--r--libmaple/stm32f1/include/series/exti.h46
-rw-r--r--libmaple/stm32f1/include/series/flash.h149
-rw-r--r--libmaple/stm32f1/include/series/gpio.h493
-rw-r--r--libmaple/stm32f1/include/series/i2c.h85
-rw-r--r--libmaple/stm32f1/include/series/nvic.h173
-rw-r--r--libmaple/stm32f1/include/series/pwr.h52
-rw-r--r--libmaple/stm32f1/include/series/rcc.h599
-rw-r--r--libmaple/stm32f1/include/series/spi.h99
-rw-r--r--libmaple/stm32f1/include/series/stm32.h219
-rw-r--r--libmaple/stm32f1/include/series/timer.h128
-rw-r--r--libmaple/stm32f1/include/series/usart.h76
-rw-r--r--libmaple/stm32f1/performance/isrs.S263
-rw-r--r--libmaple/stm32f1/performance/vector_table.S118
-rw-r--r--libmaple/stm32f1/rcc.c164
-rw-r--r--libmaple/stm32f1/rules.mk45
-rw-r--r--libmaple/stm32f1/spi.c84
-rw-r--r--libmaple/stm32f1/timer.c124
-rw-r--r--libmaple/stm32f1/usart.c170
-rw-r--r--libmaple/stm32f1/value/isrs.S270
-rw-r--r--libmaple/stm32f1/value/vector_table.S116
30 files changed, 5451 insertions, 0 deletions
diff --git a/libmaple/stm32f1/adc.c b/libmaple/stm32f1/adc.c
new file mode 100644
index 0000000..6409c37
--- /dev/null
+++ b/libmaple/stm32f1/adc.c
@@ -0,0 +1,115 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ * 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 libmaple/stm32f1/adc.c
+ * @author Marti Bolivar <mbolivar@leaflabs.com>,
+ * Perry Hung <perry@leaflabs.com>
+ * @brief STM32F1 ADC support.
+ */
+
+#include <libmaple/adc.h>
+#include <libmaple/gpio.h>
+
+/*
+ * Devices
+ */
+
+static adc_dev adc1 = {
+ .regs = ADC1_BASE,
+ .clk_id = RCC_ADC1,
+};
+/** ADC1 device. */
+const adc_dev *ADC1 = &adc1;
+
+static adc_dev adc2 = {
+ .regs = ADC2_BASE,
+ .clk_id = RCC_ADC2,
+};
+/** ADC2 device. */
+const adc_dev *ADC2 = &adc2;
+
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+static adc_dev adc3 = {
+ .regs = ADC3_BASE,
+ .clk_id = RCC_ADC3,
+};
+/** ADC3 device. */
+const adc_dev *ADC3 = &adc3;
+#endif
+
+/*
+ * STM32F1 routines
+ */
+
+/**
+ * @brief Calibrate an ADC peripheral
+ *
+ * Availability: STM32F1.
+ *
+ * @param dev adc device
+ */
+void adc_calibrate(const adc_dev *dev) {
+ __io uint32 *rstcal_bit = bb_perip(&(dev->regs->CR2), 3);
+ __io uint32 *cal_bit = bb_perip(&(dev->regs->CR2), 2);
+
+ *rstcal_bit = 1;
+ while (*rstcal_bit)
+ ;
+
+ *cal_bit = 1;
+ while (*cal_bit)
+ ;
+}
+
+/*
+ * Common routines
+ */
+
+void adc_set_prescaler(adc_prescaler pre) {
+ rcc_set_prescaler(RCC_PRESCALER_ADC, (uint32)pre);
+}
+
+void adc_foreach(void (*fn)(const adc_dev*)) {
+ fn(ADC1);
+ fn(ADC2);
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+ fn(ADC3);
+#endif
+}
+
+void adc_config_gpio(const adc_dev *ignored, gpio_dev *gdev, uint8 bit) {
+ gpio_set_mode(gdev, bit, GPIO_INPUT_ANALOG);
+}
+
+void adc_enable_single_swstart(const adc_dev *dev) {
+ adc_init(dev);
+ adc_set_extsel(dev, ADC_SWSTART);
+ adc_set_exttrig(dev, 1);
+ adc_enable(dev);
+ adc_calibrate(dev);
+}
diff --git a/libmaple/stm32f1/bkp.c b/libmaple/stm32f1/bkp.c
new file mode 100644
index 0000000..01ad419
--- /dev/null
+++ b/libmaple/stm32f1/bkp.c
@@ -0,0 +1,129 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/bkp.c
+ * @brief STM32F1 Backup register support.
+ */
+
+#include <libmaple/bkp.h>
+#include <libmaple/pwr.h>
+#include <libmaple/rcc.h>
+#include <libmaple/bitband.h>
+
+static inline __io uint32* data_register(uint8 reg);
+
+bkp_dev bkp = {
+ .regs = BKP_BASE,
+};
+/** Backup device. */
+const bkp_dev *BKP = &bkp;
+
+/**
+ * @brief Initialize backup interface.
+ *
+ * Enables the power and backup interface clocks, and resets the
+ * backup device.
+ */
+void bkp_init(void) {
+ /* Don't call pwr_init(), or you'll reset the device. We just
+ * need the clock. */
+ rcc_clk_enable(RCC_PWR);
+ rcc_clk_enable(RCC_BKP);
+ rcc_reset_dev(RCC_BKP);
+}
+
+/**
+ * Enable write access to the backup registers. Backup interface must
+ * be initialized for subsequent register writes to work.
+ * @see bkp_init()
+ */
+void bkp_enable_writes(void) {
+ *bb_perip(&PWR_BASE->CR, PWR_CR_DBP_BIT) = 1;
+}
+
+/**
+ * Disable write access to the backup registers.
+ */
+void bkp_disable_writes(void) {
+ *bb_perip(&PWR_BASE->CR, PWR_CR_DBP_BIT) = 0;
+}
+
+/**
+ * Read a value from given backup data register.
+ * @param reg Data register to read, from 1 to BKP_NR_DATA_REGS (10 on
+ * medium-density devices, 42 on high-density devices).
+ */
+uint16 bkp_read(uint8 reg) {
+ __io uint32* dr = data_register(reg);
+ if (!dr) {
+ ASSERT(0); /* nonexistent register */
+ return 0;
+ }
+ return (uint16)*dr;
+}
+
+/**
+ * @brief Write a value to given data register.
+ *
+ * Write access to backup registers must be enabled.
+ *
+ * @param reg Data register to write, from 1 to BKP_NR_DATA_REGS (10
+ * on medium-density devices, 42 on high-density devices).
+ * @param val Value to write into the register.
+ * @see bkp_enable_writes()
+ */
+void bkp_write(uint8 reg, uint16 val) {
+ __io uint32* dr = data_register(reg);
+ if (!dr) {
+ ASSERT(0); /* nonexistent register */
+ return;
+ }
+ *dr = (uint32)val;
+}
+
+/*
+ * Data register memory layout is not contiguous. It's split up from
+ * 1--NR_LOW_DRS, beginning at BKP_BASE->DR1, through to
+ * (NR_LOW_DRS+1)--BKP_NR_DATA_REGS, beginning at BKP_BASE->DR11.
+ */
+#define NR_LOW_DRS 10
+
+static inline __io uint32* data_register(uint8 reg) {
+ if (reg < 1 || reg > BKP_NR_DATA_REGS) {
+ return 0;
+ }
+
+#if BKP_NR_DATA_REGS == NR_LOW_DRS
+ return (uint32*)BKP_BASE + reg;
+#else
+ if (reg <= NR_LOW_DRS) {
+ return (uint32*)BKP_BASE + reg;
+ } else {
+ return (uint32*)&(BKP_BASE->DR11) + (reg - NR_LOW_DRS - 1);
+ }
+#endif
+}
diff --git a/libmaple/stm32f1/dma.c b/libmaple/stm32f1/dma.c
new file mode 100644
index 0000000..6400d15
--- /dev/null
+++ b/libmaple/stm32f1/dma.c
@@ -0,0 +1,413 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 Michael Hope.
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/dma.c
+ * @author Marti Bolivar <mbolivar@leaflabs.com>;
+ * Original implementation by Michael Hope
+ * @brief STM32F1 DMA support.
+ */
+
+#include <libmaple/dma.h>
+#include <libmaple/bitband.h>
+
+/* Hack to ensure inlining in dma_irq_handler() */
+#define DMA_GET_HANDLER(dev, tube) (dev->handlers[tube - 1].handler)
+#include "dma_private.h"
+
+/*
+ * Devices
+ */
+
+static dma_dev dma1 = {
+ .regs = DMA1_BASE,
+ .clk_id = RCC_DMA1,
+ .handlers = {{ .handler = NULL, .irq_line = NVIC_DMA_CH1 },
+ { .handler = NULL, .irq_line = NVIC_DMA_CH2 },
+ { .handler = NULL, .irq_line = NVIC_DMA_CH3 },
+ { .handler = NULL, .irq_line = NVIC_DMA_CH4 },
+ { .handler = NULL, .irq_line = NVIC_DMA_CH5 },
+ { .handler = NULL, .irq_line = NVIC_DMA_CH6 },
+ { .handler = NULL, .irq_line = NVIC_DMA_CH7 }},
+};
+/** STM32F1 DMA1 device */
+dma_dev *DMA1 = &dma1;
+
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+static dma_dev dma2 = {
+ .regs = DMA2_BASE,
+ .clk_id = RCC_DMA2,
+ .handlers = {{ .handler = NULL, .irq_line = NVIC_DMA2_CH1 },
+ { .handler = NULL, .irq_line = NVIC_DMA2_CH2 },
+ { .handler = NULL, .irq_line = NVIC_DMA2_CH3 },
+ { .handler = NULL, .irq_line = NVIC_DMA2_CH_4_5 },
+ { .handler = NULL, .irq_line = NVIC_DMA2_CH_4_5 }}, /* !@#$ */
+};
+/** STM32F1 DMA2 device */
+dma_dev *DMA2 = &dma2;
+#endif
+
+/*
+ * Auxiliary routines
+ */
+
+/* Can channel serve cfg->tube_req_src? */
+static int cfg_req_ok(dma_channel channel, dma_tube_config *cfg) {
+ return (cfg->tube_req_src & 0x7) == channel;
+}
+
+/* Can dev serve cfg->tube_req_src? */
+static int cfg_dev_ok(dma_dev *dev, dma_tube_config *cfg) {
+ return (rcc_clk_id)(cfg->tube_req_src >> 3) == dev->clk_id;
+}
+
+/* Is addr acceptable for use as DMA src/dst? */
+static int cfg_mem_ok(__io void *addr) {
+ enum dma_atype atype = _dma_addr_type(addr);
+ return atype == DMA_ATYPE_MEM || atype == DMA_ATYPE_PER;
+}
+
+/* Is the direction implied by src->dst supported? */
+static int cfg_dir_ok(dma_tube_config *cfg) {
+ /* We can't do peripheral->peripheral transfers. */
+ return ((_dma_addr_type(cfg->tube_src) == DMA_ATYPE_MEM) ||
+ (_dma_addr_type(cfg->tube_dst) == DMA_ATYPE_MEM));
+}
+
+static int preconfig_check(dma_dev *dev, dma_channel channel,
+ dma_tube_config *cfg) {
+ if (!cfg_req_ok(channel, cfg)) {
+ return -DMA_TUBE_CFG_EREQ;
+ }
+ if (cfg->tube_nr_xfers > 65535) {
+ return -DMA_TUBE_CFG_ENDATA;
+ }
+ if (!cfg_dev_ok(dev, cfg)) {
+ return -DMA_TUBE_CFG_EDEV;
+ }
+ if (!cfg_mem_ok(cfg->tube_src)) {
+ return -DMA_TUBE_CFG_ESRC;
+ }
+ if (!cfg_mem_ok(cfg->tube_dst)) {
+ return -DMA_TUBE_CFG_EDST;
+ }
+ if (!cfg_dir_ok(cfg)) {
+ return -DMA_TUBE_CFG_EDIR;
+ }
+ return DMA_TUBE_CFG_SUCCESS;
+}
+
+static inline void set_ccr(dma_tube_reg_map *chregs,
+ dma_xfer_size msize, int minc,
+ dma_xfer_size psize, int pinc,
+ uint32 other_flags) {
+ chregs->CCR = ((msize << 10) | (psize << 8) |
+ (minc ? DMA_CCR_MINC : 0) | (pinc ? DMA_CCR_PINC : 0) |
+ other_flags);
+}
+
+static inline uint32 cfg_ccr_flags(unsigned tube_flags) {
+ /* DMA_CFG_SRC_INC and DMA_CFG_DST_INC are special */
+ return tube_flags & ~(DMA_CFG_SRC_INC | DMA_CFG_DST_INC);
+}
+
+/* Configure chregs according to cfg, where cfg->tube_dst is peripheral. */
+static int config_to_per(dma_tube_reg_map *chregs, dma_tube_config *cfg) {
+ /* Check that ->tube_src is memory (if it's anything else, we
+ * shouldn't have been called). */
+ ASSERT(_dma_addr_type(cfg->tube_src) == DMA_ATYPE_MEM);
+
+ set_ccr(chregs,
+ cfg->tube_src_size, cfg->tube_flags & DMA_CFG_SRC_INC,
+ cfg->tube_dst_size, cfg->tube_flags & DMA_CFG_DST_INC,
+ (cfg_ccr_flags(cfg->tube_flags) | DMA_CCR_DIR_FROM_MEM));
+ chregs->CNDTR = cfg->tube_nr_xfers;
+ chregs->CMAR = (uint32)cfg->tube_src;
+ chregs->CPAR = (uint32)cfg->tube_dst;
+ return DMA_TUBE_CFG_SUCCESS;
+}
+
+/* Configure chregs according to cfg, where cfg->tube_dst is memory. */
+static int config_to_mem(dma_tube_reg_map *chregs, dma_tube_config *cfg) {
+ uint32 mem2mem;
+
+ if ((_dma_addr_type(cfg->tube_src) == DMA_ATYPE_MEM) &&
+ (cfg->tube_flags & DMA_CFG_CIRC)) {
+ /* Can't do mem-to-mem and circular mode */
+ return -DMA_TUBE_CFG_ECFG;
+ }
+
+ mem2mem = (_dma_addr_type(cfg->tube_src) == DMA_ATYPE_MEM ?
+ DMA_CCR_MEM2MEM : 0);
+ set_ccr(chregs,
+ cfg->tube_dst_size, cfg->tube_flags & DMA_CFG_DST_INC,
+ cfg->tube_src_size, cfg->tube_flags & DMA_CFG_SRC_INC,
+ (cfg_ccr_flags(cfg->tube_flags) |
+ DMA_CCR_DIR_FROM_PER |
+ mem2mem));
+ chregs->CNDTR = cfg->tube_nr_xfers;
+ chregs->CMAR = (uint32)cfg->tube_dst;
+ chregs->CPAR = (uint32)cfg->tube_src;
+ return DMA_TUBE_CFG_SUCCESS;
+}
+
+/*
+ * Routines
+ */
+
+int dma_tube_cfg(dma_dev *dev, dma_channel channel, dma_tube_config *cfg) {
+ dma_tube_reg_map *chregs;
+ int ret = preconfig_check(dev, channel, cfg);
+
+ if (ret < 0) {
+ return ret;
+ }
+
+ dma_disable(dev, channel); /* Must disable before reconfiguring */
+ dma_clear_isr_bits(dev, channel); /* For sanity and consistency
+ * with STM32F2. */
+
+ chregs = dma_tube_regs(dev, channel);
+ switch (_dma_addr_type(cfg->tube_dst)) {
+ case DMA_ATYPE_PER:
+ ret = config_to_per(chregs, cfg);
+ break;
+ case DMA_ATYPE_MEM:
+ ret = config_to_mem(chregs, cfg);
+ break;
+ default:
+ /* Can't happen */
+ ASSERT(0);
+ return -DMA_TUBE_CFG_ECFG;
+ }
+ if (ret < 0) {
+ return ret;
+ }
+ chregs->CNDTR = cfg->tube_nr_xfers;
+ return DMA_TUBE_CFG_SUCCESS;
+}
+
+void dma_set_priority(dma_dev *dev,
+ dma_channel channel,
+ dma_priority priority) {
+ dma_channel_reg_map *channel_regs;
+ uint32 ccr;
+
+ ASSERT_FAULT(!dma_is_channel_enabled(dev, channel));
+
+ channel_regs = dma_channel_regs(dev, channel);
+ ccr = channel_regs->CCR;
+ ccr &= ~DMA_CCR_PL;
+ ccr |= (priority << 12);
+ channel_regs->CCR = ccr;
+}
+
+void dma_set_num_transfers(dma_dev *dev,
+ dma_channel channel,
+ uint16 num_transfers) {
+ dma_channel_reg_map *channel_regs;
+
+ ASSERT_FAULT(!dma_is_channel_enabled(dev, channel));
+
+ channel_regs = dma_channel_regs(dev, channel);
+ channel_regs->CNDTR = num_transfers;
+}
+
+void dma_attach_interrupt(dma_dev *dev, dma_channel channel,
+ void (*handler)(void)) {
+ DMA_GET_HANDLER(dev, channel) = handler;
+ nvic_irq_enable(dev->handlers[channel - 1].irq_line);
+}
+
+void dma_detach_interrupt(dma_dev *dev, dma_channel channel) {
+ /* Don't use nvic_irq_disable()! Think about DMA2 channels 4 and 5. */
+ dma_channel_regs(dev, channel)->CCR &= ~0xF;
+ DMA_GET_HANDLER(dev, channel) = NULL;
+}
+
+void dma_enable(dma_dev *dev, dma_channel channel) {
+ dma_channel_reg_map *chan_regs = dma_channel_regs(dev, channel);
+ bb_peri_set_bit(&chan_regs->CCR, DMA_CCR_EN_BIT, 1);
+}
+
+void dma_disable(dma_dev *dev, dma_channel channel) {
+ dma_channel_reg_map *chan_regs = dma_channel_regs(dev, channel);
+ bb_peri_set_bit(&chan_regs->CCR, DMA_CCR_EN_BIT, 0);
+}
+
+dma_irq_cause dma_get_irq_cause(dma_dev *dev, dma_channel channel) {
+ /* Grab and clear the ISR bits. */
+ uint8 status_bits = dma_get_isr_bits(dev, channel);
+ dma_clear_isr_bits(dev, channel);
+
+ /* If the channel global interrupt flag is cleared, then
+ * something's very wrong. */
+ ASSERT(status_bits & 0x1);
+ /* If GIF is set, then some other flag should be set, barring
+ * something unexpected (e.g. the user making an unforeseen IFCR
+ * write). */
+ ASSERT(status_bits != 0x1);
+
+ /* ISR flags get set even if the corresponding interrupt enable
+ * bits in the channel's configuration register are cleared, so we
+ * can't use a switch here.
+ *
+ * Don't change the order of these if statements. */
+ if (status_bits & 0x8) {
+ return DMA_TRANSFER_ERROR;
+ } else if (status_bits & 0x2) {
+ return DMA_TRANSFER_COMPLETE;
+ } else if (status_bits & 0x4) {
+ return DMA_TRANSFER_HALF_COMPLETE;
+ }
+
+ /* If we get here, one of our assumptions has been violated, but
+ * the debug level is too low for the above ASSERTs() to have had
+ * any effect. In order to fail fast, mimic the DMA controller's
+ * behavior when an error occurs. */
+ dma_disable(dev, channel);
+ return DMA_TRANSFER_ERROR;
+}
+
+void dma_set_mem_addr(dma_dev *dev, dma_channel channel, __io void *addr) {
+ dma_channel_reg_map *chan_regs;
+
+ ASSERT_FAULT(!dma_is_channel_enabled(dev, channel));
+
+ chan_regs = dma_channel_regs(dev, channel);
+ chan_regs->CMAR = (uint32)addr;
+}
+
+void dma_set_per_addr(dma_dev *dev, dma_channel channel, __io void *addr) {
+ dma_channel_reg_map *chan_regs;
+
+ ASSERT_FAULT(!dma_is_channel_enabled(dev, channel));
+
+ chan_regs = dma_channel_regs(dev, channel);
+ chan_regs->CPAR = (uint32)addr;
+}
+
+/**
+ * @brief Deprecated. Use dma_tube_cfg() instead.
+ *
+ * Set up a DMA transfer.
+ *
+ * The channel will be disabled before being reconfigured. The
+ * transfer will have low priority by default. You may choose another
+ * priority before the transfer begins using dma_set_priority(), as
+ * well as performing any other configuration you desire. When the
+ * channel is configured to your liking, enable it using dma_enable().
+ *
+ * @param dev DMA device.
+ * @param channel DMA channel.
+ * @param peripheral_address Base address of peripheral data register
+ * involved in the transfer.
+ * @param peripheral_size Peripheral data transfer size.
+ * @param memory_address Base memory address involved in the transfer.
+ * @param memory_size Memory data transfer size.
+ * @param mode Logical OR of dma_mode_flags
+ *
+ * @see dma_tube_cfg()
+ *
+ * @sideeffect Disables the given DMA channel.
+ * @see dma_xfer_size
+ * @see dma_mode_flags
+ * @see dma_set_num_transfers()
+ * @see dma_set_priority()
+ * @see dma_attach_interrupt()
+ * @see dma_enable()
+ */
+__deprecated
+void dma_setup_transfer(dma_dev *dev,
+ dma_channel channel,
+ __io void *peripheral_address,
+ dma_xfer_size peripheral_size,
+ __io void *memory_address,
+ dma_xfer_size memory_size,
+ uint32 mode) {
+ dma_channel_reg_map *channel_regs = dma_channel_regs(dev, channel);
+
+ dma_disable(dev, channel); /* can't write to CMAR/CPAR otherwise */
+ channel_regs->CCR = (memory_size << 10) | (peripheral_size << 8) | mode;
+ channel_regs->CMAR = (uint32)memory_address;
+ channel_regs->CPAR = (uint32)peripheral_address;
+}
+
+/*
+ * IRQ handlers
+ */
+
+void __irq_dma1_channel1(void) {
+ dma_irq_handler(DMA1, DMA_CH1);
+}
+
+void __irq_dma1_channel2(void) {
+ dma_irq_handler(DMA1, DMA_CH2);
+}
+
+void __irq_dma1_channel3(void) {
+ dma_irq_handler(DMA1, DMA_CH3);
+}
+
+void __irq_dma1_channel4(void) {
+ dma_irq_handler(DMA1, DMA_CH4);
+}
+
+void __irq_dma1_channel5(void) {
+ dma_irq_handler(DMA1, DMA_CH5);
+}
+
+void __irq_dma1_channel6(void) {
+ dma_irq_handler(DMA1, DMA_CH6);
+}
+
+void __irq_dma1_channel7(void) {
+ dma_irq_handler(DMA1, DMA_CH7);
+}
+
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+void __irq_dma2_channel1(void) {
+ dma_irq_handler(DMA2, DMA_CH1);
+}
+
+void __irq_dma2_channel2(void) {
+ dma_irq_handler(DMA2, DMA_CH2);
+}
+
+void __irq_dma2_channel3(void) {
+ dma_irq_handler(DMA2, DMA_CH3);
+}
+
+void __irq_dma2_channel4_5(void) {
+ if ((DMA2_BASE->CCR4 & DMA_CCR_EN) && (DMA2_BASE->ISR & DMA_ISR_GIF4)) {
+ dma_irq_handler(DMA2, DMA_CH4);
+ }
+ if ((DMA2_BASE->CCR5 & DMA_CCR_EN) && (DMA2_BASE->ISR & DMA_ISR_GIF5)) {
+ dma_irq_handler(DMA2, DMA_CH5);
+ }
+}
+#endif
diff --git a/libmaple/stm32f1/exti.c b/libmaple/stm32f1/exti.c
new file mode 100644
index 0000000..b9ff401
--- /dev/null
+++ b/libmaple/stm32f1/exti.c
@@ -0,0 +1,32 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * 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.
+*****************************************************************************/
+
+#include <libmaple/gpio.h>
+#include "exti_private.h"
+
+void exti_select(exti_num num, exti_cfg port) {
+ exti_do_select(&AFIO_BASE->EXTICR1 + num / 4, num, port);
+}
diff --git a/libmaple/stm32f1/fsmc.c b/libmaple/stm32f1/fsmc.c
new file mode 100644
index 0000000..210f0be
--- /dev/null
+++ b/libmaple/stm32f1/fsmc.c
@@ -0,0 +1,95 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ * Copyright (c) 2010 Bryan Newbold.
+ *
+ * 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 libmaple/stm32f1/fsmc.c
+ * @author Marti Bolivar <mbolivar@leaflabs.com>,
+ * Bryan Newbold <bnewbold@robocracy.org>
+ * @brief STM32F1 FSMC support.
+ */
+
+#include <libmaple/stm32.h>
+
+#if STM32_HAVE_FSMC /* Don't try building the rest for MCUs without FSMC */
+
+#include <libmaple/fsmc.h>
+#include <libmaple/gpio.h>
+
+void fsmc_sram_init_gpios(void) {
+ /* Data lines... */
+ gpio_set_mode(GPIOD, 0, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOD, 1, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOD, 8, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOD, 9, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOD, 10, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOD, 14, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOD, 15, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOE, 7, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOE, 8, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOE, 9, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOE, 10, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOE, 11, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOE, 12, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOE, 13, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOE, 14, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOE, 15, GPIO_AF_OUTPUT_PP);
+
+ /* Address lines... */
+ gpio_set_mode(GPIOD, 11, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOD, 12, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOD, 13, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOF, 0, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOF, 1, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOF, 2, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOF, 3, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOF, 4, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOF, 5, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOF, 12, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOF, 13, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOF, 14, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOF, 15, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOG, 0, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOG, 1, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOG, 2, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOG, 3, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOG, 4, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(GPIOG, 5, GPIO_AF_OUTPUT_PP);
+
+ /* And control lines... */
+ gpio_set_mode(GPIOD, 4, GPIO_AF_OUTPUT_PP); // NOE
+ gpio_set_mode(GPIOD, 5, GPIO_AF_OUTPUT_PP); // NWE
+
+ gpio_set_mode(GPIOD, 7, GPIO_AF_OUTPUT_PP); // NE1
+ gpio_set_mode(GPIOG, 9, GPIO_AF_OUTPUT_PP); // NE2
+ gpio_set_mode(GPIOG, 10, GPIO_AF_OUTPUT_PP); // NE3
+ gpio_set_mode(GPIOG, 12, GPIO_AF_OUTPUT_PP); // NE4
+
+ gpio_set_mode(GPIOE, 0, GPIO_AF_OUTPUT_PP); // NBL0
+ gpio_set_mode(GPIOE, 1, GPIO_AF_OUTPUT_PP); // NBL1
+}
+
+#endif /* STM32_HAVE_FSMC */
diff --git a/libmaple/stm32f1/gpio.c b/libmaple/stm32f1/gpio.c
new file mode 100644
index 0000000..4b596e9
--- /dev/null
+++ b/libmaple/stm32f1/gpio.c
@@ -0,0 +1,166 @@
+/******************************************************************************
+ * 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 libmaple/stm32f1/gpio.c
+ * @brief STM32F1 GPIO support.
+ */
+
+#include <libmaple/gpio.h>
+#include <libmaple/rcc.h>
+
+/*
+ * GPIO devices
+ */
+
+gpio_dev gpioa = {
+ .regs = GPIOA_BASE,
+ .clk_id = RCC_GPIOA,
+ .exti_port = EXTI_PA,
+};
+/** GPIO port A device. */
+gpio_dev* const GPIOA = &gpioa;
+
+gpio_dev gpiob = {
+ .regs = GPIOB_BASE,
+ .clk_id = RCC_GPIOB,
+ .exti_port = EXTI_PB,
+};
+/** GPIO port B device. */
+gpio_dev* const GPIOB = &gpiob;
+
+gpio_dev gpioc = {
+ .regs = GPIOC_BASE,
+ .clk_id = RCC_GPIOC,
+ .exti_port = EXTI_PC,
+};
+/** GPIO port C device. */
+gpio_dev* const GPIOC = &gpioc;
+
+gpio_dev gpiod = {
+ .regs = GPIOD_BASE,
+ .clk_id = RCC_GPIOD,
+ .exti_port = EXTI_PD,
+};
+/** GPIO port D device. */
+gpio_dev* const GPIOD = &gpiod;
+
+#ifdef STM32_HIGH_DENSITY
+gpio_dev gpioe = {
+ .regs = GPIOE_BASE,
+ .clk_id = RCC_GPIOE,
+ .exti_port = EXTI_PE,
+};
+/** GPIO port E device. */
+gpio_dev* const GPIOE = &gpioe;
+
+gpio_dev gpiof = {
+ .regs = GPIOF_BASE,
+ .clk_id = RCC_GPIOF,
+ .exti_port = EXTI_PF,
+};
+/** GPIO port F device. */
+gpio_dev* const GPIOF = &gpiof;
+
+gpio_dev gpiog = {
+ .regs = GPIOG_BASE,
+ .clk_id = RCC_GPIOG,
+ .exti_port = EXTI_PG,
+};
+/** GPIO port G device. */
+gpio_dev* const GPIOG = &gpiog;
+#endif
+
+/*
+ * GPIO routines
+ */
+
+/**
+ * Initialize and reset all available GPIO devices.
+ */
+void gpio_init_all(void) {
+ gpio_init(GPIOA);
+ gpio_init(GPIOB);
+ gpio_init(GPIOC);
+ gpio_init(GPIOD);
+#ifdef STM32_HIGH_DENSITY
+ gpio_init(GPIOE);
+ gpio_init(GPIOF);
+ gpio_init(GPIOG);
+#endif
+}
+
+/**
+ * Set the mode of a GPIO pin.
+ *
+ * @param dev GPIO device.
+ * @param pin Pin on the device whose mode to set, 0--15.
+ * @param mode General purpose or alternate function mode to set the pin to.
+ * @see gpio_pin_mode
+ */
+void gpio_set_mode(gpio_dev *dev, uint8 pin, gpio_pin_mode mode) {
+ gpio_reg_map *regs = dev->regs;
+ __io uint32 *cr = &regs->CRL + (pin >> 3);
+ uint32 shift = (pin & 0x7) * 4;
+ uint32 tmp = *cr;
+
+ tmp &= ~(0xF << shift);
+ tmp |= (mode == GPIO_INPUT_PU ? GPIO_INPUT_PD : mode) << shift;
+ *cr = tmp;
+
+ if (mode == GPIO_INPUT_PD) {
+ regs->ODR &= ~(1U << pin);
+ } else if (mode == GPIO_INPUT_PU) {
+ regs->ODR |= (1U << pin);
+ }
+}
+
+/*
+ * AFIO
+ */
+
+/**
+ * @brief Initialize the AFIO clock, and reset the AFIO registers.
+ */
+void afio_init(void) {
+ rcc_clk_enable(RCC_AFIO);
+ rcc_reset_dev(RCC_AFIO);
+}
+
+#define AFIO_EXTI_SEL_MASK 0xF
+
+/**
+ * @brief Perform an alternate function remap.
+ * @param remapping Remapping to perform.
+ */
+void afio_remap(afio_remap_peripheral remapping) {
+ if (remapping & AFIO_REMAP_USE_MAPR2) {
+ remapping &= ~AFIO_REMAP_USE_MAPR2;
+ AFIO_BASE->MAPR2 |= remapping;
+ } else {
+ AFIO_BASE->MAPR |= remapping;
+ }
+}
diff --git a/libmaple/stm32f1/i2c.c b/libmaple/stm32f1/i2c.c
new file mode 100644
index 0000000..8439793
--- /dev/null
+++ b/libmaple/stm32f1/i2c.c
@@ -0,0 +1,129 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/i2c.c
+ * @brief STM32F1 I2C support
+ */
+
+#include "i2c_private.h"
+#include <libmaple/i2c.h>
+
+/*
+ * Devices
+ */
+
+static i2c_dev i2c1 = I2C_DEV_OLD(1, &gpiob, 7, 6);
+static i2c_dev i2c2 = I2C_DEV_OLD(2, &gpiob, 11, 10);
+
+/** STM32F1 I2C device 1 */
+i2c_dev* const I2C1 = &i2c1;
+/** STM32F1 I2C device 2 */
+i2c_dev* const I2C2 = &i2c2;
+
+/*
+ * Routines
+ */
+
+static int i2c1_wants_remap(const i2c_dev *dev) {
+ /* Check if we've got I2C1 configured for SDA/SCL remap on PB9/PB8 */
+ return (dev->clk_id == RCC_I2C1) &&
+ (scl_port(dev)->clk_id == RCC_GPIOB) &&
+ (sda_port(dev)->clk_id == RCC_GPIOB) &&
+ (dev->sda_pin == 9) &&
+ (dev->scl_pin == 8);
+}
+
+void i2c_config_gpios(const i2c_dev *dev) {
+ if (i2c1_wants_remap(dev)) {
+ afio_remap(AFIO_REMAP_I2C1);
+ }
+ gpio_set_mode(sda_port(dev), dev->sda_pin, GPIO_AF_OUTPUT_OD);
+ gpio_set_mode(scl_port(dev), dev->scl_pin, GPIO_AF_OUTPUT_OD);
+}
+
+void i2c_master_release_bus(const i2c_dev *dev) {
+ gpio_write_bit(scl_port(dev), dev->scl_pin, 1);
+ gpio_write_bit(sda_port(dev), dev->sda_pin, 1);
+ gpio_set_mode(scl_port(dev), dev->scl_pin, GPIO_OUTPUT_OD);
+ gpio_set_mode(sda_port(dev), dev->sda_pin, GPIO_OUTPUT_OD);
+}
+
+/*
+ * IRQ handlers
+ */
+
+void __irq_i2c1_ev(void) {
+ _i2c_irq_handler(I2C1);
+}
+
+void __irq_i2c2_ev(void) {
+ _i2c_irq_handler(I2C2);
+}
+
+void __irq_i2c1_er(void) {
+ _i2c_irq_error_handler(I2C1);
+}
+
+void __irq_i2c2_er(void) {
+ _i2c_irq_error_handler(I2C2);
+}
+
+/*
+ * Internal APIs
+ */
+
+void _i2c_irq_priority_fixup(i2c_dev *dev) {
+ /*
+ * Important STM32 Errata:
+ *
+ * See STM32F10xx8 and STM32F10xxB Errata sheet (Doc ID 14574 Rev 8),
+ * Section 2.11.1, 2.11.2.
+ *
+ * 2.11.1:
+ * When the EV7, EV7_1, EV6_1, EV6_3, EV2, EV8, and EV3 events are not
+ * managed before the current byte is being transferred, problems may be
+ * encountered such as receiving an extra byte, reading the same data twice
+ * or missing data.
+ *
+ * 2.11.2:
+ * In Master Receiver mode, when closing the communication using
+ * method 2, the content of the last read data can be corrupted.
+ *
+ * If the user software is not able to read the data N-1 before the STOP
+ * condition is generated on the bus, the content of the shift register
+ * (data N) will be corrupted. (data N is shifted 1-bit to the left).
+ *
+ * ----------------------------------------------------------------------
+ *
+ * In order to ensure that events are not missed, the i2c interrupt must
+ * not be preempted. We set the i2c interrupt priority to be the highest
+ * interrupt in the system (priority level 0). All other interrupts have
+ * been initialized to priority level 16. See nvic_init().
+ */
+ nvic_irq_set_priority(dev->ev_nvic_line, 0);
+ nvic_irq_set_priority(dev->er_nvic_line, 0);
+}
diff --git a/libmaple/stm32f1/include/series/adc.h b/libmaple/stm32f1/include/series/adc.h
new file mode 100644
index 0000000..79d8107
--- /dev/null
+++ b/libmaple/stm32f1/include/series/adc.h
@@ -0,0 +1,253 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ * 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 libmaple/stm32f1/include/series/adc.h
+ * @author Marti Bolivar <mbolivar@leaflabs.com>,
+ * Perry Hung <perry@leaflabs.com>
+ * @brief STM32F1 ADC header.
+ */
+
+#ifndef _LIBMAPLE_STM32F1_ADC_H_
+#define _LIBMAPLE_STM32F1_ADC_H_
+
+#include <libmaple/bitband.h>
+#include <libmaple/libmaple_types.h>
+#include <libmaple/rcc.h> /* For the prescalers */
+
+/*
+ * Devices
+ */
+
+extern const struct adc_dev *ADC1;
+extern const struct adc_dev *ADC2;
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+extern const struct adc_dev *ADC3;
+#endif
+
+/*
+ * Register map base pointers
+ */
+
+/** STM32F1 ADC1 register map base pointer. */
+#define ADC1_BASE ((struct adc_reg_map*)0x40012400)
+/** STM32F1 ADC2 register map base pointer. */
+#define ADC2_BASE ((struct adc_reg_map*)0x40012800)
+/** STM32F1 ADC3 register map base pointer. */
+#define ADC3_BASE ((struct adc_reg_map*)0x40013C00)
+
+/*
+ * Register bit definitions
+ */
+
+/* Control register 2 */
+
+#define ADC_CR2_ADON_BIT 0
+#define ADC_CR2_CONT_BIT 1
+#define ADC_CR2_CAL_BIT 2
+#define ADC_CR2_RSTCAL_BIT 3
+#define ADC_CR2_DMA_BIT 8
+#define ADC_CR2_ALIGN_BIT 11
+#define ADC_CR2_JEXTTRIG_BIT 15
+#define ADC_CR2_EXTTRIG_BIT 20
+#define ADC_CR2_JSWSTART_BIT 21
+#define ADC_CR2_SWSTART_BIT 22
+#define ADC_CR2_TSEREFE_BIT 23
+
+#define ADC_CR2_ADON (1U << ADC_CR2_ADON_BIT)
+#define ADC_CR2_CONT (1U << ADC_CR2_CONT_BIT)
+#define ADC_CR2_CAL (1U << ADC_CR2_CAL_BIT)
+#define ADC_CR2_RSTCAL (1U << ADC_CR2_RSTCAL_BIT)
+#define ADC_CR2_DMA (1U << ADC_CR2_DMA_BIT)
+#define ADC_CR2_ALIGN (1U << ADC_CR2_ALIGN_BIT)
+#define ADC_CR2_JEXTSEL 0x7000
+#define ADC_CR2_JEXTTRIG (1U << ADC_CR2_JEXTTRIG_BIT)
+#define ADC_CR2_EXTSEL 0xE0000
+#define ADC_CR2_EXTTRIG (1U << ADC_CR2_EXTTRIG_BIT)
+#define ADC_CR2_JSWSTART (1U << ADC_CR2_JSWSTART_BIT)
+#define ADC_CR2_SWSTART (1U << ADC_CR2_SWSTART_BIT)
+#define ADC_CR2_TSEREFE (1U << ADC_CR2_TSEREFE_BIT)
+
+/*
+ * Other types
+ */
+
+/**
+ * @brief STM32F1 external event selectors for regular group
+ * conversion.
+ *
+ * Some external events are only available on ADCs 1 and 2, others
+ * only on ADC3, while others are available on all three ADCs.
+ * Additionally, some events are only available on high- and
+ * XL-density STM32F1 MCUs, as they use peripherals only available on
+ * those MCU densities.
+ *
+ * For ease of use, each event selector is given along with the ADCs
+ * it's available on, along with any other availability restrictions.
+ *
+ * @see adc_set_extsel()
+ */
+typedef enum adc_extsel_event {
+ /* TODO: Smarten this up a bit, as follows.
+ *
+ * The EXTSEL bits on F1 are a little brain-damaged in that the
+ * TIM8 TRGO event has different bits depending on whether you're
+ * using ADC1/2 or ADC3. We route around this by declaring two
+ * enumerators, ADC_EXT_EV_ADC12_TIM8_TRGO and
+ * ADC_EXT_EV_ADC3_TIM8_TRGO.
+ *
+ * The right thing to do is to provide a single
+ * ADC_EXT_EV_TIM8_TRGO enumerator and override adc_set_extsel on
+ * STM32F1 to handle this situation correctly. We can do that
+ * later, though, and change the per-ADC enumerator values to
+ * ADC_EXT_EV_TIM8_TRGO to preserve compatibility. */
+
+ /* ADC1 and ADC2 only: */
+ ADC_EXT_EV_TIM1_CC1 = 0x00000, /**< ADC1, ADC2: Timer 1 CC1 event */
+ ADC_EXT_EV_TIM1_CC2 = 0x20000, /**< ADC1, ADC2: Timer 1 CC2 event */
+ ADC_EXT_EV_TIM2_CC2 = 0x60000, /**< ADC1, ADC2: Timer 2 CC2 event */
+ ADC_EXT_EV_TIM3_TRGO = 0x80000, /**< ADC1, ADC2: Timer 3 TRGO event */
+ ADC_EXT_EV_TIM4_CC4 = 0xA0000, /**< ADC1, ADC2: Timer 4 CC4 event */
+ ADC_EXT_EV_EXTI11 = 0xC0000, /**< ADC1, ADC2: EXTI11 event */
+
+ /* Common: */
+ ADC_EXT_EV_TIM1_CC3 = 0x40000, /**< ADC1, ADC2, ADC3: Timer 1 CC3 event */
+ ADC_EXT_EV_SWSTART = 0xE0000, /**< ADC1, ADC2, ADC3: Software start */
+
+ /* HD only: */
+ ADC_EXT_EV_TIM3_CC1 = 0x00000, /**<
+ * ADC3: Timer 3 CC1 event
+ * Availability: high- and XL-density. */
+ ADC_EXT_EV_TIM2_CC3 = 0x20000, /**<
+ * ADC3: Timer 2 CC3 event
+ * Availability: high- and XL-density. */
+ ADC_EXT_EV_TIM8_CC1 = 0x60000, /**<
+ * ADC3: Timer 8 CC1 event
+ * Availability: high- and XL-density. */
+ ADC_EXT_EV_ADC3_TIM8_TRGO = 0x80000, /**<
+ * ADC3: Timer 8 TRGO event
+ * Availability: high- and XL-density. */
+ ADC_EXT_EV_TIM5_CC1 = 0xA0000, /**<
+ * ADC3: Timer 5 CC1 event
+ * Availability: high- and XL-density. */
+ ADC_EXT_EV_ADC12_TIM8_TRGO = 0xC0000, /**<
+ * ADC1, ADC2: Timer 8 TRGO event
+ * Availability: high- and XL-density. */
+ ADC_EXT_EV_TIM5_CC3 = 0xC0000, /**<
+ * ADC3: Timer 5 CC3 event
+ * Availability: high- and XL-density. */
+} adc_extsel_event;
+
+/* We'll keep these old adc_extsel_event enumerators around for a
+ * while, for backwards compatibility: */
+/** Deprecated. Use ADC_EXT_EV_TIM1_CC1 instead. */
+#define ADC_ADC12_TIM1_CC1 ADC_EXT_EV_TIM1_CC1
+/** Deprecated. Use ADC_EXT_EV_TIM1_CC2 instead. */
+#define ADC_ADC12_TIM1_CC2 ADC_EXT_EV_TIM1_CC2
+/** Deprecated. Use ADC_EXT_EV_TIM1_CC3 instead. */
+#define ADC_ADC12_TIM1_CC3 ADC_EXT_EV_TIM1_CC3
+/** Deprecated. Use ADC_EXT_EV_TIM2_CC2 instead. */
+#define ADC_ADC12_TIM2_CC2 ADC_EXT_EV_TIM2_CC2
+/** Deprecated. Use ADC_EXT_EV_TIM3_TRGO instead. */
+#define ADC_ADC12_TIM3_TRGO ADC_EXT_EV_TIM3_TRGO
+/** Deprecated. Use ADC_EXT_EV_TIM4_CC4 instead. */
+#define ADC_ADC12_TIM4_CC4 ADC_EXT_EV_TIM4_CC4
+/** Deprecated. Use ADC_EXT_EV_EXTI11 instead. */
+#define ADC_ADC12_EXTI11 ADC_EXT_EV_EXTI11
+/** Deprecated. Use ADC_EXT_EV_ADC12_TIM8_TRGO instead. */
+#define ADC_ADC12_TIM8_TRGO ADC_EXT_EV_ADC12_TIM8_TRGO
+/** Deprecated. Use ADC_EXT_EV_SWSTART instead. */
+#define ADC_ADC12_SWSTART ADC_EXT_EV_SWSTART
+/** Deprecated. Use ADC_EXT_EV_TIM1_CC1 instead. */
+#define ADC_ADC3_TIM3_CC1 ADC_EXT_EV_TIM1_CC1
+/** Deprecated. Use ADC_EXT_EV_TIM1_CC2 instead. */
+#define ADC_ADC3_TIM2_CC3 ADC_EXT_EV_TIM1_CC2
+/** Deprecated. Use ADC_EXT_EV_TIM1_CC3 instead. */
+#define ADC_ADC3_TIM1_CC3 ADC_EXT_EV_TIM1_CC3
+/** Deprecated. Use ADC_EXT_EV_TIM2_CC2 instead. */
+#define ADC_ADC3_TIM8_CC1 ADC_EXT_EV_TIM2_CC2
+/** Deprecated. Use ADC_EXT_EV_TIM3_TRGO instead. */
+#define ADC_ADC3_TIM8_TRGO ADC_EXT_EV_TIM3_TRGO
+/** Deprecated. Use ADC_EXT_EV_TIM4_CC4 instead. */
+#define ADC_ADC3_TIM5_CC1 ADC_EXT_EV_TIM4_CC4
+/** Deprecated. Use ADC_EXT_EV_EXTI11 instead. */
+#define ADC_ADC3_TIM5_CC3 ADC_EXT_EV_EXTI11
+/** Deprecated. Use ADC_EXT_EV_TIM8_TRGO instead. */
+#define ADC_ADC3_SWSTART ADC_EXT_EV_TIM8_TRGO
+/** Deprecated. Use ADC_EXT_EV_SWSTART instead. */
+#define ADC_SWSTART ADC_EXT_EV_SWSTART
+
+/**
+ * @brief STM32F1 sample times, in ADC clock cycles.
+ *
+ * These control the amount of time spent sampling the input voltage.
+ */
+typedef enum adc_smp_rate {
+ ADC_SMPR_1_5, /**< 1.5 ADC cycles */
+ ADC_SMPR_7_5, /**< 7.5 ADC cycles */
+ ADC_SMPR_13_5, /**< 13.5 ADC cycles */
+ ADC_SMPR_28_5, /**< 28.5 ADC cycles */
+ ADC_SMPR_41_5, /**< 41.5 ADC cycles */
+ ADC_SMPR_55_5, /**< 55.5 ADC cycles */
+ ADC_SMPR_71_5, /**< 71.5 ADC cycles */
+ ADC_SMPR_239_5, /**< 239.5 ADC cycles */
+} adc_smp_rate;
+
+/**
+ * @brief STM32F1 ADC prescalers, as divisors of PCLK2.
+ */
+typedef enum adc_prescaler {
+ /** PCLK2 divided by 2 */
+ ADC_PRE_PCLK2_DIV_2 = RCC_ADCPRE_PCLK_DIV_2,
+ /** PCLK2 divided by 4 */
+ ADC_PRE_PCLK2_DIV_4 = RCC_ADCPRE_PCLK_DIV_4,
+ /** PCLK2 divided by 6 */
+ ADC_PRE_PCLK2_DIV_6 = RCC_ADCPRE_PCLK_DIV_6,
+ /** PCLK2 divided by 8 */
+ ADC_PRE_PCLK2_DIV_8 = RCC_ADCPRE_PCLK_DIV_8,
+} adc_prescaler;
+
+/*
+ * Routines
+ */
+
+void adc_calibrate(const adc_dev *dev);
+
+/**
+ * @brief Set external trigger conversion mode event for regular channels
+ *
+ * Availability: STM32F1.
+ *
+ * @param dev ADC device
+ * @param enable If 1, conversion on external events is enabled; if 0,
+ * disabled.
+ */
+static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) {
+ *bb_perip(&dev->regs->CR2, ADC_CR2_EXTTRIG_BIT) = !!enable;
+}
+
+#endif
diff --git a/libmaple/stm32f1/include/series/dac.h b/libmaple/stm32f1/include/series/dac.h
new file mode 100644
index 0000000..c0d026b
--- /dev/null
+++ b/libmaple/stm32f1/include/series/dac.h
@@ -0,0 +1,71 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/include/series/dac.h
+ * @brief STM32F1 DAC support
+ */
+
+#ifndef _LIBMAPLE_STM32F1_DAC_H_
+#define _LIBMAPLE_STM32F1_DAC_H_
+
+#ifdef __cplusplus
+extern "C"{
+#endif
+
+#include <libmaple/libmaple_types.h>
+
+/** STM32F1 DAC register map type. */
+typedef struct dac_reg_map {
+ __io uint32 CR; /**< Control register */
+ __io uint32 SWTRIGR; /**< Software trigger register */
+ __io uint32 DHR12R1; /**< Channel 1 12-bit right-aligned data
+ holding register */
+ __io uint32 DHR12L1; /**< Channel 1 12-bit left-aligned data
+ holding register */
+ __io uint32 DHR8R1; /**< Channel 1 8-bit left-aligned data
+ holding register */
+ __io uint32 DHR12R2; /**< Channel 2 12-bit right-aligned data
+ holding register */
+ __io uint32 DHR12L2; /**< Channel 2 12-bit left-aligned data
+ holding register */
+ __io uint32 DHR8R2; /**< Channel 2 8-bit left-aligned data
+ holding register */
+ __io uint32 DHR12RD; /**< Dual DAC 12-bit right-aligned data
+ holding register */
+ __io uint32 DHR12LD; /**< Dual DAC 12-bit left-aligned data
+ holding register */
+ __io uint32 DHR8RD; /**< Dual DAC 8-bit right-aligned data holding
+ register */
+ __io uint32 DOR1; /**< Channel 1 data output register */
+ __io uint32 DOR2; /**< Channel 2 data output register */
+} dac_reg_map;
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/libmaple/stm32f1/include/series/dma.h b/libmaple/stm32f1/include/series/dma.h
new file mode 100644
index 0000000..bedb602
--- /dev/null
+++ b/libmaple/stm32f1/include/series/dma.h
@@ -0,0 +1,575 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 Michael Hope.
+ * Copyright (c) 2012 LeafLabs, LLC
+ *
+ * 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 libmaple/stm32f1/include/series/dma.h
+ * @author Marti Bolivar <mbolivar@leaflabs.com>;
+ * Original implementation by Michael Hope
+ * @brief STM32F1 DMA series header.
+ */
+
+/*
+ * See /notes/dma-stm32f1.txt for more information.
+ */
+
+#ifndef _LIBMAPLE_STM32F1_DMA_H_
+#define _LIBMAPLE_STM32F1_DMA_H_
+
+#ifdef __cplusplus
+extern "C"{
+#endif
+
+#include <libmaple/libmaple_types.h>
+#include <libmaple/dma_common.h>
+
+/*
+ * Register maps and base pointers
+ */
+
+/**
+ * @brief STM32F1 DMA register map type.
+ *
+ * Note that DMA controller 2 (register map base pointer DMA2_BASE)
+ * only supports channels 1--5.
+ */
+typedef struct dma_reg_map {
+ __io uint32 ISR; /**< Interrupt status register */
+ __io uint32 IFCR; /**< Interrupt flag clear register */
+ __io uint32 CCR1; /**< Channel 1 configuration register */
+ __io uint32 CNDTR1; /**< Channel 1 number of data register */
+ __io uint32 CPAR1; /**< Channel 1 peripheral address register */
+ __io uint32 CMAR1; /**< Channel 1 memory address register */
+ const uint32 RESERVED1; /**< Reserved. */
+ __io uint32 CCR2; /**< Channel 2 configuration register */
+ __io uint32 CNDTR2; /**< Channel 2 number of data register */
+ __io uint32 CPAR2; /**< Channel 2 peripheral address register */
+ __io uint32 CMAR2; /**< Channel 2 memory address register */
+ const uint32 RESERVED2; /**< Reserved. */
+ __io uint32 CCR3; /**< Channel 3 configuration register */
+ __io uint32 CNDTR3; /**< Channel 3 number of data register */
+ __io uint32 CPAR3; /**< Channel 3 peripheral address register */
+ __io uint32 CMAR3; /**< Channel 3 memory address register */
+ const uint32 RESERVED3; /**< Reserved. */
+ __io uint32 CCR4; /**< Channel 4 configuration register */
+ __io uint32 CNDTR4; /**< Channel 4 number of data register */
+ __io uint32 CPAR4; /**< Channel 4 peripheral address register */
+ __io uint32 CMAR4; /**< Channel 4 memory address register */
+ const uint32 RESERVED4; /**< Reserved. */
+ __io uint32 CCR5; /**< Channel 5 configuration register */
+ __io uint32 CNDTR5; /**< Channel 5 number of data register */
+ __io uint32 CPAR5; /**< Channel 5 peripheral address register */
+ __io uint32 CMAR5; /**< Channel 5 memory address register */
+ const uint32 RESERVED5; /**< Reserved. */
+ __io uint32 CCR6; /**< Channel 6 configuration register */
+ __io uint32 CNDTR6; /**< Channel 6 number of data register */
+ __io uint32 CPAR6; /**< Channel 6 peripheral address register */
+ __io uint32 CMAR6; /**< Channel 6 memory address register */
+ const uint32 RESERVED6; /**< Reserved. */
+ __io uint32 CCR7; /**< Channel 7 configuration register */
+ __io uint32 CNDTR7; /**< Channel 7 number of data register */
+ __io uint32 CPAR7; /**< Channel 7 peripheral address register */
+ __io uint32 CMAR7; /**< Channel 7 memory address register */
+ const uint32 RESERVED7; /**< Reserved. */
+} dma_reg_map;
+
+/** DMA controller 1 register map base pointer */
+#define DMA1_BASE ((struct dma_reg_map*)0x40020000)
+/** DMA controller 2 register map base pointer */
+#define DMA2_BASE ((struct dma_reg_map*)0x40020400)
+
+/**
+ * @brief STM32F1 DMA channel (i.e. tube) register map type.
+ * Provides access to an individual channel's registers.
+ * @see dma_tube_regs()
+ */
+typedef struct dma_tube_reg_map {
+ __io uint32 CCR; /**< Channel configuration register */
+ __io uint32 CNDTR; /**< Channel number of data register */
+ __io uint32 CPAR; /**< Channel peripheral address register */
+ __io uint32 CMAR; /**< Channel memory address register */
+} dma_tube_reg_map;
+
+/** DMA1 channel 1 register map base pointer */
+#define DMA1CH1_BASE ((struct dma_tube_reg_map*)0x40020008)
+/** DMA1 channel 2 register map base pointer */
+#define DMA1CH2_BASE ((struct dma_tube_reg_map*)0x4002001C)
+/** DMA1 channel 3 register map base pointer */
+#define DMA1CH3_BASE ((struct dma_tube_reg_map*)0x40020030)
+/** DMA1 channel 4 register map base pointer */
+#define DMA1CH4_BASE ((struct dma_tube_reg_map*)0x40020044)
+/** DMA1 channel 5 register map base pointer */
+#define DMA1CH5_BASE ((struct dma_tube_reg_map*)0x40020058)
+/** DMA1 channel 6 register map base pointer */
+#define DMA1CH6_BASE ((struct dma_tube_reg_map*)0x4002006C)
+/** DMA1 channel 7 register map base pointer */
+#define DMA1CH7_BASE ((struct dma_tube_reg_map*)0x40020080)
+
+/** DMA2 channel 1 register map base pointer */
+#define DMA2CH1_BASE ((struct dma_tube_reg_map*)0x40020408)
+/** DMA2 channel 2 register map base pointer */
+#define DMA2CH2_BASE ((struct dma_tube_reg_map*)0x4002041C)
+/** DMA2 channel 3 register map base pointer */
+#define DMA2CH3_BASE ((struct dma_tube_reg_map*)0x40020430)
+/** DMA2 channel 4 register map base pointer */
+#define DMA2CH4_BASE ((struct dma_tube_reg_map*)0x40020444)
+/** DMA2 channel 5 register map base pointer */
+#define DMA2CH5_BASE ((struct dma_tube_reg_map*)0x40020458)
+
+/*
+ * Register bit definitions
+ */
+
+/* Interrupt status register */
+
+#define DMA_ISR_TEIF_BIT 3
+#define DMA_ISR_HTIF_BIT 2
+#define DMA_ISR_TCIF_BIT 1
+#define DMA_ISR_GIF_BIT 0
+
+#define DMA_ISR_TEIF (1 << DMA_ISR_TEIF_BIT)
+#define DMA_ISR_HTIF (1 << DMA_ISR_HTIF_BIT)
+#define DMA_ISR_TCID (1 << DMA_ISR_TCIF_BIT)
+#define DMA_ISR_GIF (1 << DMA_ISR_GIF_BIT)
+
+#define DMA_ISR_TEIF7_BIT 27
+#define DMA_ISR_HTIF7_BIT 26
+#define DMA_ISR_TCIF7_BIT 25
+#define DMA_ISR_GIF7_BIT 24
+#define DMA_ISR_TEIF6_BIT 23
+#define DMA_ISR_HTIF6_BIT 22
+#define DMA_ISR_TCIF6_BIT 21
+#define DMA_ISR_GIF6_BIT 20
+#define DMA_ISR_TEIF5_BIT 19
+#define DMA_ISR_HTIF5_BIT 18
+#define DMA_ISR_TCIF5_BIT 17
+#define DMA_ISR_GIF5_BIT 16
+#define DMA_ISR_TEIF4_BIT 15
+#define DMA_ISR_HTIF4_BIT 14
+#define DMA_ISR_TCIF4_BIT 13
+#define DMA_ISR_GIF4_BIT 12
+#define DMA_ISR_TEIF3_BIT 11
+#define DMA_ISR_HTIF3_BIT 10
+#define DMA_ISR_TCIF3_BIT 9
+#define DMA_ISR_GIF3_BIT 8
+#define DMA_ISR_TEIF2_BIT 7
+#define DMA_ISR_HTIF2_BIT 6
+#define DMA_ISR_TCIF2_BIT 5
+#define DMA_ISR_GIF2_BIT 4
+#define DMA_ISR_TEIF1_BIT 3
+#define DMA_ISR_HTIF1_BIT 2
+#define DMA_ISR_TCIF1_BIT 1
+#define DMA_ISR_GIF1_BIT 0
+
+#define DMA_ISR_TEIF7 (1U << DMA_ISR_TEIF7_BIT)
+#define DMA_ISR_HTIF7 (1U << DMA_ISR_HTIF7_BIT)
+#define DMA_ISR_TCIF7 (1U << DMA_ISR_TCIF7_BIT)
+#define DMA_ISR_GIF7 (1U << DMA_ISR_GIF7_BIT)
+#define DMA_ISR_TEIF6 (1U << DMA_ISR_TEIF6_BIT)
+#define DMA_ISR_HTIF6 (1U << DMA_ISR_HTIF6_BIT)
+#define DMA_ISR_TCIF6 (1U << DMA_ISR_TCIF6_BIT)
+#define DMA_ISR_GIF6 (1U << DMA_ISR_GIF6_BIT)
+#define DMA_ISR_TEIF5 (1U << DMA_ISR_TEIF5_BIT)
+#define DMA_ISR_HTIF5 (1U << DMA_ISR_HTIF5_BIT)
+#define DMA_ISR_TCIF5 (1U << DMA_ISR_TCIF5_BIT)
+#define DMA_ISR_GIF5 (1U << DMA_ISR_GIF5_BIT)
+#define DMA_ISR_TEIF4 (1U << DMA_ISR_TEIF4_BIT)
+#define DMA_ISR_HTIF4 (1U << DMA_ISR_HTIF4_BIT)
+#define DMA_ISR_TCIF4 (1U << DMA_ISR_TCIF4_BIT)
+#define DMA_ISR_GIF4 (1U << DMA_ISR_GIF4_BIT)
+#define DMA_ISR_TEIF3 (1U << DMA_ISR_TEIF3_BIT)
+#define DMA_ISR_HTIF3 (1U << DMA_ISR_HTIF3_BIT)
+#define DMA_ISR_TCIF3 (1U << DMA_ISR_TCIF3_BIT)
+#define DMA_ISR_GIF3 (1U << DMA_ISR_GIF3_BIT)
+#define DMA_ISR_TEIF2 (1U << DMA_ISR_TEIF2_BIT)
+#define DMA_ISR_HTIF2 (1U << DMA_ISR_HTIF2_BIT)
+#define DMA_ISR_TCIF2 (1U << DMA_ISR_TCIF2_BIT)
+#define DMA_ISR_GIF2 (1U << DMA_ISR_GIF2_BIT)
+#define DMA_ISR_TEIF1 (1U << DMA_ISR_TEIF1_BIT)
+#define DMA_ISR_HTIF1 (1U << DMA_ISR_HTIF1_BIT)
+#define DMA_ISR_TCIF1 (1U << DMA_ISR_TCIF1_BIT)
+#define DMA_ISR_GIF1 (1U << DMA_ISR_GIF1_BIT)
+
+/* Interrupt flag clear register */
+
+#define DMA_IFCR_CTEIF7_BIT 27
+#define DMA_IFCR_CHTIF7_BIT 26
+#define DMA_IFCR_CTCIF7_BIT 25
+#define DMA_IFCR_CGIF7_BIT 24
+#define DMA_IFCR_CTEIF6_BIT 23
+#define DMA_IFCR_CHTIF6_BIT 22
+#define DMA_IFCR_CTCIF6_BIT 21
+#define DMA_IFCR_CGIF6_BIT 20
+#define DMA_IFCR_CTEIF5_BIT 19
+#define DMA_IFCR_CHTIF5_BIT 18
+#define DMA_IFCR_CTCIF5_BIT 17
+#define DMA_IFCR_CGIF5_BIT 16
+#define DMA_IFCR_CTEIF4_BIT 15
+#define DMA_IFCR_CHTIF4_BIT 14
+#define DMA_IFCR_CTCIF4_BIT 13
+#define DMA_IFCR_CGIF4_BIT 12
+#define DMA_IFCR_CTEIF3_BIT 11
+#define DMA_IFCR_CHTIF3_BIT 10
+#define DMA_IFCR_CTCIF3_BIT 9
+#define DMA_IFCR_CGIF3_BIT 8
+#define DMA_IFCR_CTEIF2_BIT 7
+#define DMA_IFCR_CHTIF2_BIT 6
+#define DMA_IFCR_CTCIF2_BIT 5
+#define DMA_IFCR_CGIF2_BIT 4
+#define DMA_IFCR_CTEIF1_BIT 3
+#define DMA_IFCR_CHTIF1_BIT 2
+#define DMA_IFCR_CTCIF1_BIT 1
+#define DMA_IFCR_CGIF1_BIT 0
+
+#define DMA_IFCR_CTEIF7 (1U << DMA_IFCR_CTEIF7_BIT)
+#define DMA_IFCR_CHTIF7 (1U << DMA_IFCR_CHTIF7_BIT)
+#define DMA_IFCR_CTCIF7 (1U << DMA_IFCR_CTCIF7_BIT)
+#define DMA_IFCR_CGIF7 (1U << DMA_IFCR_CGIF7_BIT)
+#define DMA_IFCR_CTEIF6 (1U << DMA_IFCR_CTEIF6_BIT)
+#define DMA_IFCR_CHTIF6 (1U << DMA_IFCR_CHTIF6_BIT)
+#define DMA_IFCR_CTCIF6 (1U << DMA_IFCR_CTCIF6_BIT)
+#define DMA_IFCR_CGIF6 (1U << DMA_IFCR_CGIF6_BIT)
+#define DMA_IFCR_CTEIF5 (1U << DMA_IFCR_CTEIF5_BIT)
+#define DMA_IFCR_CHTIF5 (1U << DMA_IFCR_CHTIF5_BIT)
+#define DMA_IFCR_CTCIF5 (1U << DMA_IFCR_CTCIF5_BIT)
+#define DMA_IFCR_CGIF5 (1U << DMA_IFCR_CGIF5_BIT)
+#define DMA_IFCR_CTEIF4 (1U << DMA_IFCR_CTEIF4_BIT)
+#define DMA_IFCR_CHTIF4 (1U << DMA_IFCR_CHTIF4_BIT)
+#define DMA_IFCR_CTCIF4 (1U << DMA_IFCR_CTCIF4_BIT)
+#define DMA_IFCR_CGIF4 (1U << DMA_IFCR_CGIF4_BIT)
+#define DMA_IFCR_CTEIF3 (1U << DMA_IFCR_CTEIF3_BIT)
+#define DMA_IFCR_CHTIF3 (1U << DMA_IFCR_CHTIF3_BIT)
+#define DMA_IFCR_CTCIF3 (1U << DMA_IFCR_CTCIF3_BIT)
+#define DMA_IFCR_CGIF3 (1U << DMA_IFCR_CGIF3_BIT)
+#define DMA_IFCR_CTEIF2 (1U << DMA_IFCR_CTEIF2_BIT)
+#define DMA_IFCR_CHTIF2 (1U << DMA_IFCR_CHTIF2_BIT)
+#define DMA_IFCR_CTCIF2 (1U << DMA_IFCR_CTCIF2_BIT)
+#define DMA_IFCR_CGIF2 (1U << DMA_IFCR_CGIF2_BIT)
+#define DMA_IFCR_CTEIF1 (1U << DMA_IFCR_CTEIF1_BIT)
+#define DMA_IFCR_CHTIF1 (1U << DMA_IFCR_CHTIF1_BIT)
+#define DMA_IFCR_CTCIF1 (1U << DMA_IFCR_CTCIF1_BIT)
+#define DMA_IFCR_CGIF1 (1U << DMA_IFCR_CGIF1_BIT)
+
+/* Channel configuration register */
+
+#define DMA_CCR_MEM2MEM_BIT 14
+#define DMA_CCR_MINC_BIT 7
+#define DMA_CCR_PINC_BIT 6
+#define DMA_CCR_CIRC_BIT 5
+#define DMA_CCR_DIR_BIT 4
+#define DMA_CCR_TEIE_BIT 3
+#define DMA_CCR_HTIE_BIT 2
+#define DMA_CCR_TCIE_BIT 1
+#define DMA_CCR_EN_BIT 0
+
+#define DMA_CCR_MEM2MEM (1U << DMA_CCR_MEM2MEM_BIT)
+#define DMA_CCR_PL (0x3 << 12)
+#define DMA_CCR_PL_LOW (0x0 << 12)
+#define DMA_CCR_PL_MEDIUM (0x1 << 12)
+#define DMA_CCR_PL_HIGH (0x2 << 12)
+#define DMA_CCR_PL_VERY_HIGH (0x3 << 12)
+#define DMA_CCR_MSIZE (0x3 << 10)
+#define DMA_CCR_MSIZE_8BITS (0x0 << 10)
+#define DMA_CCR_MSIZE_16BITS (0x1 << 10)
+#define DMA_CCR_MSIZE_32BITS (0x2 << 10)
+#define DMA_CCR_PSIZE (0x3 << 8)
+#define DMA_CCR_PSIZE_8BITS (0x0 << 8)
+#define DMA_CCR_PSIZE_16BITS (0x1 << 8)
+#define DMA_CCR_PSIZE_32BITS (0x2 << 8)
+#define DMA_CCR_MINC (1U << DMA_CCR_MINC_BIT)
+#define DMA_CCR_PINC (1U << DMA_CCR_PINC_BIT)
+#define DMA_CCR_CIRC (1U << DMA_CCR_CIRC_BIT)
+#define DMA_CCR_DIR (1U << DMA_CCR_DIR_BIT)
+#define DMA_CCR_DIR_FROM_PER (0U << DMA_CCR_DIR_BIT)
+#define DMA_CCR_DIR_FROM_MEM (1U << DMA_CCR_DIR_BIT)
+#define DMA_CCR_TEIE (1U << DMA_CCR_TEIE_BIT)
+#define DMA_CCR_HTIE (1U << DMA_CCR_HTIE_BIT)
+#define DMA_CCR_TCIE (1U << DMA_CCR_TCIE_BIT)
+#define DMA_CCR_EN (1U << DMA_CCR_EN_BIT)
+
+/*
+ * Devices
+ */
+
+extern dma_dev *DMA1;
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+extern dma_dev *DMA2;
+#endif
+
+/*
+ * Other types needed by, or useful for, <libmaple/dma.h>.
+ */
+
+/**
+ * @brief STM32F1 dma_tube.
+ * On STM32F1, DMA tubes are just channels.
+ */
+#define dma_tube dma_channel
+
+/**
+ * @brief On STM32F1, dma_channel_reg_map is an alias for dma_tube_reg_map.
+ * This is for backwards compatibility. */
+#define dma_channel_reg_map dma_tube_reg_map
+
+/**
+ * @brief STM32F1 configuration flags for dma_tube_config
+ * @see struct dma_tube_config
+ */
+typedef enum dma_cfg_flags {
+ /**
+ * Source address increment mode
+ *
+ * If this flag is set, the source address is incremented (by the
+ * source size) after each DMA transfer.
+ */
+ DMA_CFG_SRC_INC = 1U << 31,
+
+ /**
+ * Destination address increment mode
+ *
+ * If this flag is set, the destination address is incremented (by
+ * the destination size) after each DMA transfer.
+ */
+ DMA_CFG_DST_INC = 1U << 30,
+
+ /**
+ * Circular mode
+ *
+ * This mode is not available for memory-to-memory transfers.
+ */
+ DMA_CFG_CIRC = DMA_CCR_CIRC,
+
+ /** Transfer complete interrupt enable */
+ DMA_CFG_CMPLT_IE = DMA_CCR_TCIE,
+ /** Transfer half-complete interrupt enable */
+ DMA_CFG_HALF_CMPLT_IE = DMA_CCR_HTIE,
+ /** Transfer error interrupt enable */
+ DMA_CFG_ERR_IE = DMA_CCR_TEIE,
+} dma_cfg_flags;
+
+/**
+ * @brief STM32F1 DMA request sources.
+ *
+ * IMPORTANT:
+ *
+ * 1. On STM32F1, each dma_request_src can only be used by a
+ * particular tube on a particular DMA controller. For example,
+ * DMA_REQ_SRC_ADC1 belongs to DMA1, tube 1. DMA2 cannot serve
+ * requests from ADC1, nor can DMA1 tube 2, etc. If you try to use a
+ * request source with the wrong DMA controller or tube on STM32F1,
+ * dma_tube_cfg() will fail.
+ *
+ * 2. In general, a DMA tube can only serve a single request source at
+ * a time, and on STM32F1, Terrible Super-Bad Things will happen if
+ * two request sources are active for a single tube.
+ *
+ * To make all this easier to sort out, these dma_request_src
+ * enumerators are grouped by DMA controller and tube.
+ *
+ * @see struct dma_tube_config
+ * @see dma_tube_cfg()
+ */
+typedef enum dma_request_src {
+ /* Each request source encodes the DMA controller and channel it
+ * belongs to, for error checking in dma_tube_cfg(). */
+
+ /* DMA1 request sources */
+
+ /**@{*/
+ /** (DMA1, tube 1) */
+ DMA_REQ_SRC_ADC1 = (RCC_DMA1 << 3) | 1,
+ DMA_REQ_SRC_TIM2_CH3 = (RCC_DMA1 << 3) | 1,
+ DMA_REQ_SRC_TIM4_CH1 = (RCC_DMA1 << 3) | 1,
+ /**@}*/
+
+ /**@{*/
+ /** (DMA1, tube 2)*/
+ DMA_REQ_SRC_SPI1_RX = (RCC_DMA1 << 3) | 2,
+ DMA_REQ_SRC_USART3_TX = (RCC_DMA1 << 3) | 2,
+ DMA_REQ_SRC_TIM1_CH1 = (RCC_DMA1 << 3) | 2,
+ DMA_REQ_SRC_TIM2_UP = (RCC_DMA1 << 3) | 2,
+ DMA_REQ_SRC_TIM3_CH3 = (RCC_DMA1 << 3) | 2,
+ /**@}*/
+
+ /**@{*/
+ /** (DMA1, tube 3)*/
+ DMA_REQ_SRC_SPI1_TX = (RCC_DMA1 << 3) | 3,
+ DMA_REQ_SRC_USART3_RX = (RCC_DMA1 << 3) | 3,
+ DMA_REQ_SRC_TIM1_CH2 = (RCC_DMA1 << 3) | 3,
+ DMA_REQ_SRC_TIM3_CH4 = (RCC_DMA1 << 3) | 3,
+ DMA_REQ_SRC_TIM3_UP = (RCC_DMA1 << 3) | 3,
+ /**@}*/
+
+ /**@{*/
+ /** (DMA1, tube 4)*/
+ DMA_REQ_SRC_SPI2_RX = (RCC_DMA1 << 3) | 4,
+ DMA_REQ_SRC_I2S2_RX = (RCC_DMA1 << 3) | 4,
+ DMA_REQ_SRC_USART1_TX = (RCC_DMA1 << 3) | 4,
+ DMA_REQ_SRC_I2C2_TX = (RCC_DMA1 << 3) | 4,
+ DMA_REQ_SRC_TIM1_CH4 = (RCC_DMA1 << 3) | 4,
+ DMA_REQ_SRC_TIM1_TRIG = (RCC_DMA1 << 3) | 4,
+ DMA_REQ_SRC_TIM1_COM = (RCC_DMA1 << 3) | 4,
+ DMA_REQ_SRC_TIM4_CH2 = (RCC_DMA1 << 3) | 4,
+ /**@}*/
+
+ /**@{*/
+ /** (DMA1, tube 5)*/
+ DMA_REQ_SRC_SPI2_TX = (RCC_DMA1 << 3) | 5,
+ DMA_REQ_SRC_I2S2_TX = (RCC_DMA1 << 3) | 5,
+ DMA_REQ_SRC_USART1_RX = (RCC_DMA1 << 3) | 5,
+ DMA_REQ_SRC_I2C2_RX = (RCC_DMA1 << 3) | 5,
+ DMA_REQ_SRC_TIM1_UP = (RCC_DMA1 << 3) | 5,
+ DMA_REQ_SRC_TIM2_CH1 = (RCC_DMA1 << 3) | 5,
+ DMA_REQ_SRC_TIM4_CH3 = (RCC_DMA1 << 3) | 5,
+ /**@}*/
+
+ /**@{*/
+ /** (DMA1, tube 6)*/
+ DMA_REQ_SRC_USART2_RX = (RCC_DMA1 << 3) | 6,
+ DMA_REQ_SRC_I2C1_TX = (RCC_DMA1 << 3) | 6,
+ DMA_REQ_SRC_TIM1_CH3 = (RCC_DMA1 << 3) | 6,
+ DMA_REQ_SRC_TIM3_CH1 = (RCC_DMA1 << 3) | 6,
+ DMA_REQ_SRC_TIM3_TRIG = (RCC_DMA1 << 3) | 6,
+ /**@}*/
+
+ /**@{*/
+ /* Tube 7 */
+ DMA_REQ_SRC_USART2_TX = (RCC_DMA1 << 3) | 7,
+ DMA_REQ_SRC_I2C1_RX = (RCC_DMA1 << 3) | 7,
+ DMA_REQ_SRC_TIM2_CH2 = (RCC_DMA1 << 3) | 7,
+ DMA_REQ_SRC_TIM2_CH4 = (RCC_DMA1 << 3) | 7,
+ DMA_REQ_SRC_TIM4_UP = (RCC_DMA1 << 3) | 7,
+ /**@}*/
+
+ /* DMA2 request sources */
+
+ /**@{*/
+ /** (DMA2, tube 1)*/
+ DMA_REQ_SRC_SPI3_RX = (RCC_DMA2 << 3) | 1,
+ DMA_REQ_SRC_I2S3_RX = (RCC_DMA2 << 3) | 1,
+ DMA_REQ_SRC_TIM5_CH4 = (RCC_DMA2 << 3) | 1,
+ DMA_REQ_SRC_TIM5_TRIG = (RCC_DMA2 << 3) | 1,
+ /**@}*/
+
+ /**@{*/
+ /** (DMA2, tube 2)*/
+ DMA_REQ_SRC_SPI3_TX = (RCC_DMA2 << 3) | 2,
+ DMA_REQ_SRC_I2S3_TX = (RCC_DMA2 << 3) | 2,
+ DMA_REQ_SRC_TIM5_CH3 = (RCC_DMA2 << 3) | 2,
+ DMA_REQ_SRC_TIM5_UP = (RCC_DMA2 << 3) | 2,
+ /**@}*/
+
+ /**@{*/
+ /** (DMA2, tube 3)*/
+ DMA_REQ_SRC_UART4_RX = (RCC_DMA2 << 3) | 3,
+ DMA_REQ_SRC_TIM6_UP = (RCC_DMA2 << 3) | 3,
+ DMA_REQ_SRC_DAC_CH1 = (RCC_DMA2 << 3) | 3,
+ /**@}*/
+
+ /**@{*/
+ /** (DMA2, tube 4)*/
+ DMA_REQ_SRC_SDIO = (RCC_DMA2 << 3) | 4,
+ DMA_REQ_SRC_TIM5_CH2 = (RCC_DMA2 << 3) | 4,
+ /**@}*/
+
+ /**@{*/
+ /** (DMA2, tube 5)*/
+ DMA_REQ_SRC_ADC3 = (RCC_DMA2 << 3) | 5,
+ DMA_REQ_SRC_UART4_TX = (RCC_DMA2 << 3) | 5,
+ DMA_REQ_SRC_TIM5_CH1 = (RCC_DMA2 << 3) | 5,
+ /**@}*/
+} dma_request_src;
+
+/*
+ * Convenience routines.
+ */
+
+/**
+ * @brief On STM32F1, dma_is_channel_enabled() is an alias for
+ * dma_is_enabled().
+ * This is for backwards compatibility.
+ */
+#define dma_is_channel_enabled dma_is_enabled
+
+#define DMA_CHANNEL_NREGS 5 /* accounts for reserved word */
+static inline dma_tube_reg_map* dma_tube_regs(dma_dev *dev, dma_tube tube) {
+ __io uint32 *ccr1 = &dev->regs->CCR1;
+ return (dma_channel_reg_map*)(ccr1 + DMA_CHANNEL_NREGS * (tube - 1));
+}
+
+/**
+ * @brief On STM32F1, dma_channel_regs() is an alias for dma_tube_regs().
+ * This is for backwards compatibility. */
+#define dma_channel_regs(dev, ch) dma_tube_regs(dev, ch)
+
+static inline uint8 dma_is_enabled(dma_dev *dev, dma_tube tube) {
+ return (uint8)(dma_tube_regs(dev, tube)->CCR & DMA_CCR_EN);
+}
+
+static inline uint8 dma_get_isr_bits(dma_dev *dev, dma_tube tube) {
+ uint8 shift = (tube - 1) * 4;
+ return (dev->regs->ISR >> shift) & 0xF;
+}
+
+static inline void dma_clear_isr_bits(dma_dev *dev, dma_tube tube) {
+ dev->regs->IFCR = (1U << (4 * (tube - 1)));
+}
+
+/**
+ * @brief Deprecated
+ * STM32F1 mode flags for dma_setup_xfer(). Use dma_tube_cfg() instead.
+ * @see dma_tube_cfg()
+ */
+typedef enum dma_mode_flags {
+ DMA_MEM_2_MEM = 1 << 14, /**< Memory to memory mode */
+ DMA_MINC_MODE = 1 << 7, /**< Auto-increment memory address */
+ DMA_PINC_MODE = 1 << 6, /**< Auto-increment peripheral address */
+ DMA_CIRC_MODE = 1 << 5, /**< Circular mode */
+ DMA_FROM_MEM = 1 << 4, /**< Read from memory to peripheral */
+ DMA_TRNS_ERR = 1 << 3, /**< Interrupt on transfer error */
+ DMA_HALF_TRNS = 1 << 2, /**< Interrupt on half-transfer */
+ DMA_TRNS_CMPLT = 1 << 1 /**< Interrupt on transfer completion */
+} dma_mode_flags;
+
+/* Keep this around for backwards compatibility, but it's deprecated.
+ * New code should use dma_tube_cfg() instead.
+ *
+ * (It's not possible to fully configure a DMA stream on F2 with just
+ * this information, so this interface is too tied to the F1.) */
+__deprecated
+void dma_setup_transfer(dma_dev *dev,
+ dma_channel channel,
+ __io void *peripheral_address,
+ dma_xfer_size peripheral_size,
+ __io void *memory_address,
+ dma_xfer_size memory_size,
+ uint32 mode);
+
+#ifdef __cplusplus
+} // extern "C"
+#endif
+
+#endif
diff --git a/libmaple/stm32f1/include/series/exti.h b/libmaple/stm32f1/include/series/exti.h
new file mode 100644
index 0000000..1ece664
--- /dev/null
+++ b/libmaple/stm32f1/include/series/exti.h
@@ -0,0 +1,46 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/include/series/exti.h
+ * @brief STM32F1 external interrupts
+ */
+
+#ifndef _LIBMAPLE_STM32F1_EXTI_H_
+#define _LIBMAPLE_STM32F1_EXTI_H_
+
+#ifdef __cpluspus
+extern "C" {
+#endif
+
+struct exti_reg_map;
+#define EXTI_BASE ((struct exti_reg_map*)0x40010400)
+
+#ifdef __cpluspus
+}
+#endif
+
+#endif
diff --git a/libmaple/stm32f1/include/series/flash.h b/libmaple/stm32f1/include/series/flash.h
new file mode 100644
index 0000000..24efb0b
--- /dev/null
+++ b/libmaple/stm32f1/include/series/flash.h
@@ -0,0 +1,149 @@
+/******************************************************************************
+ * 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 libmaple/stm32f1/include/series/flash.h
+ * @brief STM32F1 Flash header.
+ *
+ * Provides register map, base pointer, and register bit definitions
+ * for the Flash controller on the STM32F1 line, along with
+ * series-specific configuration values.
+ */
+
+#ifndef _LIBMAPLE_STM32F1_FLASH_H_
+#define _LIBMAPLE_STM32F1_FLASH_H_
+
+#ifdef __cplusplus
+extern "C"{
+#endif
+
+#include <libmaple/libmaple_types.h>
+
+/*
+ * Register map
+ */
+
+/** @brief STM32F1 Flash register map type */
+typedef struct flash_reg_map {
+ __io uint32 ACR; /**< Access control register */
+ __io uint32 KEYR; /**< Key register */
+ __io uint32 OPTKEYR; /**< OPTKEY register */
+ __io uint32 SR; /**< Status register */
+ __io uint32 CR; /**< Control register */
+ __io uint32 AR; /**< Address register */
+ __io uint32 OBR; /**< Option byte register */
+ __io uint32 WRPR; /**< Write protection register */
+} flash_reg_map;
+
+#define FLASH_BASE ((struct flash_reg_map*)0x40022000)
+
+/*
+ * Register bit definitions
+ */
+
+/* Access control register */
+
+#define FLASH_ACR_PRFTBS_BIT 5
+#define FLASH_ACR_PRFTBE_BIT 4
+#define FLASH_ACR_HLFCYA_BIT 3
+
+#define FLASH_ACR_PRFTBS (1U << FLASH_ACR_PRFTBS_BIT)
+#define FLASH_ACR_PRFTBE (1U << FLASH_ACR_PRFTBE_BIT)
+#define FLASH_ACR_HLFCYA (1U << FLASH_ACR_HLFCYA_BIT)
+#define FLASH_ACR_LATENCY 0x7
+
+/* Status register */
+
+#define FLASH_SR_EOP_BIT 5
+#define FLASH_SR_WRPRTERR_BIT 4
+#define FLASH_SR_PGERR_BIT 2
+#define FLASH_SR_BSY_BIT 0
+
+#define FLASH_SR_EOP (1U << FLASH_SR_EOP_BIT)
+#define FLASH_SR_WRPRTERR (1U << FLASH_SR_WRPRTERR_BIT)
+#define FLASH_SR_PGERR (1U << FLASH_SR_PGERR_BIT)
+#define FLASH_SR_BSY (1U << FLASH_SR_BSY_BIT)
+
+/* Control register */
+
+#define FLASH_CR_EOPIE_BIT 12
+#define FLASH_CR_ERRIE_BIT 10
+#define FLASH_CR_OPTWRE_BIT 9
+#define FLASH_CR_LOCK_BIT 7
+#define FLASH_CR_STRT_BIT 6
+#define FLASH_CR_OPTER_BIT 5
+#define FLASH_CR_OPTPG_BIT 4
+#define FLASH_CR_MER_BIT 2
+#define FLASH_CR_PER_BIT 1
+#define FLASH_CR_PG_BIT 0
+
+#define FLASH_CR_EOPIE (1U << FLASH_CR_EOPIE_BIT)
+#define FLASH_CR_ERRIE (1U << FLASH_CR_ERRIE_BIT)
+#define FLASH_CR_OPTWRE (1U << FLASH_CR_OPTWRE_BIT)
+#define FLASH_CR_LOCK (1U << FLASH_CR_LOCK_BIT)
+#define FLASH_CR_STRT (1U << FLASH_CR_STRT_BIT)
+#define FLASH_CR_OPTER (1U << FLASH_CR_OPTER_BIT)
+#define FLASH_CR_OPTPG (1U << FLASH_CR_OPTPG_BIT)
+#define FLASH_CR_MER (1U << FLASH_CR_MER_BIT)
+#define FLASH_CR_PER (1U << FLASH_CR_PER_BIT)
+#define FLASH_CR_PG (1U << FLASH_CR_PG_BIT)
+
+/* Option byte register */
+
+#define FLASH_OBR_nRST_STDBY_BIT 4
+#define FLASH_OBR_nRST_STOP_BIT 3
+#define FLASH_OBR_WDG_SW_BIT 2
+#define FLASH_OBR_RDPRT_BIT 1
+#define FLASH_OBR_OPTERR_BIT 0
+
+#define FLASH_OBR_DATA1 (0xFF << 18)
+#define FLASH_OBR_DATA0 (0xFF << 10)
+#define FLASH_OBR_USER 0x3FF
+#define FLASH_OBR_nRST_STDBY (1U << FLASH_OBR_nRST_STDBY_BIT)
+#define FLASH_OBR_nRST_STOP (1U << FLASH_OBR_nRST_STOP_BIT)
+#define FLASH_OBR_WDG_SW (1U << FLASH_OBR_WDG_SW_BIT)
+#define FLASH_OBR_RDPRT (1U << FLASH_OBR_RDPRT_BIT)
+#define FLASH_OBR_OPTERR (1U << FLASH_OBR_OPTERR_BIT)
+
+/*
+ * Series-specific configuration values.
+ */
+
+#define FLASH_SAFE_WAIT_STATES FLASH_WAIT_STATE_2
+
+/* Flash memory features available via ACR */
+enum {
+ FLASH_PREFETCH = 0x10,
+ FLASH_HALF_CYCLE = 0x8,
+ FLASH_ICACHE = 0x0, /* Not available on STM32F1 */
+ FLASH_DCACHE = 0x0, /* Not available on STM32F1 */
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/libmaple/stm32f1/include/series/gpio.h b/libmaple/stm32f1/include/series/gpio.h
new file mode 100644
index 0000000..aecf911
--- /dev/null
+++ b/libmaple/stm32f1/include/series/gpio.h
@@ -0,0 +1,493 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/include/series/gpio.h
+ * @brief STM32F1 GPIO and AFIO support.
+ * General purpose I/O (GPIO) and Alternate Function I/O (AFIO).
+ */
+
+#ifndef _LIBMAPLE_STM32F1_GPIO_H_
+#define _LIBMAPLE_STM32F1_GPIO_H_
+
+#ifdef __cplusplus
+extern "C"{
+#endif
+
+#include <libmaple/stm32.h>
+#include <libmaple/libmaple_types.h>
+#include <libmaple/exti.h>
+
+/*
+ * GPIO register maps and devices
+ */
+
+/** GPIO register map type */
+typedef struct gpio_reg_map {
+ __io uint32 CRL; /**< Port configuration register low */
+ __io uint32 CRH; /**< Port configuration register high */
+ __io uint32 IDR; /**< Port input data register */
+ __io uint32 ODR; /**< Port output data register */
+ __io uint32 BSRR; /**< Port bit set/reset register */
+ __io uint32 BRR; /**< Port bit reset register */
+ __io uint32 LCKR; /**< Port configuration lock register */
+} gpio_reg_map;
+
+struct gpio_dev;
+extern struct gpio_dev gpioa;
+extern struct gpio_dev* const GPIOA;
+extern struct gpio_dev gpiob;
+extern struct gpio_dev* const GPIOB;
+extern struct gpio_dev gpioc;
+extern struct gpio_dev* const GPIOC;
+extern struct gpio_dev gpiod;
+extern struct gpio_dev* const GPIOD;
+#ifdef STM32_HIGH_DENSITY
+extern struct gpio_dev gpioe;
+extern struct gpio_dev* const GPIOE;
+extern struct gpio_dev gpiof;
+extern struct gpio_dev* const GPIOF;
+extern struct gpio_dev gpiog;
+extern struct gpio_dev* const GPIOG;
+#endif
+
+/** GPIO port A register map base pointer */
+#define GPIOA_BASE ((struct gpio_reg_map*)0x40010800)
+/** GPIO port B register map base pointer */
+#define GPIOB_BASE ((struct gpio_reg_map*)0x40010C00)
+/** GPIO port C register map base pointer */
+#define GPIOC_BASE ((struct gpio_reg_map*)0x40011000)
+/** GPIO port D register map base pointer */
+#define GPIOD_BASE ((struct gpio_reg_map*)0x40011400)
+/** GPIO port E register map base pointer */
+#define GPIOE_BASE ((struct gpio_reg_map*)0x40011800)
+/** GPIO port F register map base pointer */
+#define GPIOF_BASE ((struct gpio_reg_map*)0x40011C00)
+/** GPIO port G register map base pointer */
+#define GPIOG_BASE ((struct gpio_reg_map*)0x40012000)
+
+/*
+ * GPIO register bit definitions
+ */
+
+/* Control registers, low and high */
+
+#define GPIO_CR_CNF (0x3 << 2)
+#define GPIO_CR_CNF_INPUT_ANALOG (0x0 << 2)
+#define GPIO_CR_CNF_INPUT_FLOATING (0x1 << 2)
+#define GPIO_CR_CNF_INPUT_PU_PD (0x2 << 2)
+#define GPIO_CR_CNF_OUTPUT_PP (0x0 << 2)
+#define GPIO_CR_CNF_OUTPUT_OD (0x1 << 2)
+#define GPIO_CR_CNF_AF_OUTPUT_PP (0x2 << 2)
+#define GPIO_CR_CNF_AF_OUTPUT_OD (0x3 << 2)
+#define GPIO_CR_MODE 0x3
+#define GPIO_CR_MODE_INPUT 0x0
+#define GPIO_CR_MODE_OUTPUT_10MHZ 0x1
+#define GPIO_CR_MODE_OUTPUT_2MHZ 0x2
+#define GPIO_CR_MODE_OUTPUT_50MHZ 0x3
+
+/**
+ * @brief GPIO pin modes.
+ *
+ * These only allow for 50MHZ max output speeds; if you want slower,
+ * use direct register access.
+ */
+typedef enum gpio_pin_mode {
+ /** Output push-pull. */
+ GPIO_OUTPUT_PP = GPIO_CR_CNF_OUTPUT_PP | GPIO_CR_MODE_OUTPUT_50MHZ,
+ /** Output open-drain. */
+ GPIO_OUTPUT_OD = GPIO_CR_CNF_OUTPUT_OD | GPIO_CR_MODE_OUTPUT_50MHZ,
+ /** Alternate function output push-pull. */
+ GPIO_AF_OUTPUT_PP = GPIO_CR_CNF_AF_OUTPUT_PP | GPIO_CR_MODE_OUTPUT_50MHZ,
+ /** Alternate function output open drain. */
+ GPIO_AF_OUTPUT_OD = GPIO_CR_CNF_AF_OUTPUT_OD | GPIO_CR_MODE_OUTPUT_50MHZ,
+ /** Analog input. */
+ GPIO_INPUT_ANALOG = GPIO_CR_CNF_INPUT_ANALOG | GPIO_CR_MODE_INPUT,
+ /** Input floating. */
+ GPIO_INPUT_FLOATING = GPIO_CR_CNF_INPUT_FLOATING | GPIO_CR_MODE_INPUT,
+ /** Input pull-down. */
+ GPIO_INPUT_PD = GPIO_CR_CNF_INPUT_PU_PD | GPIO_CR_MODE_INPUT,
+ /** Input pull-up. */
+ GPIO_INPUT_PU, /* (treated a special case, for ODR twiddling) */
+} gpio_pin_mode;
+
+/* Hacks for F2: */
+#define GPIO_MODE_ANALOG GPIO_INPUT_ANALOG
+#define GPIO_MODE_OUTPUT GPIO_OUTPUT_PP
+
+/*
+ * AFIO register map
+ */
+
+/** AFIO register map */
+typedef struct afio_reg_map {
+ __io uint32 EVCR; /**< Event control register. */
+ __io uint32 MAPR; /**< AF remap and debug I/O configuration register. */
+ __io uint32 EXTICR1; /**< External interrupt configuration register 1. */
+ __io uint32 EXTICR2; /**< External interrupt configuration register 2. */
+ __io uint32 EXTICR3; /**< External interrupt configuration register 3. */
+ __io uint32 EXTICR4; /**< External interrupt configuration register 4. */
+ __io uint32 MAPR2; /**<
+ * AF remap and debug I/O configuration register 2. */
+} afio_reg_map;
+
+/** AFIO register map base pointer. */
+#define AFIO_BASE ((struct afio_reg_map *)0x40010000)
+
+/*
+ * AFIO register bit definitions
+ */
+
+/* Event control register */
+
+#define AFIO_EVCR_EVOE (0x1 << 7)
+#define AFIO_EVCR_PORT_PA (0x0 << 4)
+#define AFIO_EVCR_PORT_PB (0x1 << 4)
+#define AFIO_EVCR_PORT_PC (0x2 << 4)
+#define AFIO_EVCR_PORT_PD (0x3 << 4)
+#define AFIO_EVCR_PORT_PE (0x4 << 4)
+#define AFIO_EVCR_PIN_0 0x0
+#define AFIO_EVCR_PIN_1 0x1
+#define AFIO_EVCR_PIN_2 0x2
+#define AFIO_EVCR_PIN_3 0x3
+#define AFIO_EVCR_PIN_4 0x4
+#define AFIO_EVCR_PIN_5 0x5
+#define AFIO_EVCR_PIN_6 0x6
+#define AFIO_EVCR_PIN_7 0x7
+#define AFIO_EVCR_PIN_8 0x8
+#define AFIO_EVCR_PIN_9 0x9
+#define AFIO_EVCR_PIN_10 0xA
+#define AFIO_EVCR_PIN_11 0xB
+#define AFIO_EVCR_PIN_12 0xC
+#define AFIO_EVCR_PIN_13 0xD
+#define AFIO_EVCR_PIN_14 0xE
+#define AFIO_EVCR_PIN_15 0xF
+
+/* AF remap and debug I/O configuration register */
+
+#define AFIO_MAPR_SWJ_CFG (0x7 << 24)
+#define AFIO_MAPR_SWJ_CFG_FULL_SWJ (0x0 << 24)
+#define AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_NJRST (0x1 << 24)
+#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
+#define AFIO_MAPR_SWJ_CFG_NO_JTAG_NO_SW (0x4 << 24)
+#define AFIO_MAPR_ADC2_ETRGREG_REMAP (1U << 20)
+#define AFIO_MAPR_ADC2_ETRGINJ_REMAP (1U << 19)
+#define AFIO_MAPR_ADC1_ETRGREG_REMAP (1U << 18)
+#define AFIO_MAPR_ADC1_ETRGINJ_REMAP (1U << 17)
+#define AFIO_MAPR_TIM5CH4_IREMAP (1U << 16)
+#define AFIO_MAPR_PD01_REMAP (1U << 15)
+#define AFIO_MAPR_CAN_REMAP (0x3 << 13)
+#define AFIO_MAPR_CAN_REMAP_NONE (0x0 << 13)
+#define AFIO_MAPR_CAN_REMAP_PB8_PB9 (0x2 << 13)
+#define AFIO_MAPR_CAN_REMAP_PD0_PD1 (0x3 << 13)
+#define AFIO_MAPR_TIM4_REMAP (1U << 12)
+#define AFIO_MAPR_TIM3_REMAP (0x3 << 10)
+#define AFIO_MAPR_TIM3_REMAP_NONE (0x0 << 10)
+#define AFIO_MAPR_TIM3_REMAP_PARTIAL (0x2 << 10)
+#define AFIO_MAPR_TIM3_REMAP_FULL (0x3 << 10)
+#define AFIO_MAPR_TIM2_REMAP (0x3 << 8)
+#define AFIO_MAPR_TIM2_REMAP_NONE (0x0 << 8)
+#define AFIO_MAPR_TIM2_REMAP_PA15_PB3_PA2_PA3 (0x1 << 8)
+#define AFIO_MAPR_TIM2_REMAP_PA0_PA1_PB10_PB11 (0x2 << 8)
+#define AFIO_MAPR_TIM2_REMAP_FULL (0x3 << 8)
+#define AFIO_MAPR_TIM1_REMAP (0x3 << 6)
+#define AFIO_MAPR_TIM1_REMAP_NONE (0x0 << 6)
+#define AFIO_MAPR_TIM1_REMAP_PARTIAL (0x1 << 6)
+#define AFIO_MAPR_TIM1_REMAP_FULL (0x3 << 6)
+#define AFIO_MAPR_USART3_REMAP (0x3 << 4)
+#define AFIO_MAPR_USART3_REMAP_NONE (0x0 << 4)
+#define AFIO_MAPR_USART3_REMAP_PARTIAL (0x1 << 4)
+#define AFIO_MAPR_USART3_REMAP_FULL (0x3 << 4)
+#define AFIO_MAPR_USART2_REMAP (1U << 3)
+#define AFIO_MAPR_USART1_REMAP (1U << 2)
+#define AFIO_MAPR_I2C1_REMAP (1U << 1)
+#define AFIO_MAPR_SPI1_REMAP (1U << 0)
+
+/* External interrupt configuration register 1 */
+
+#define AFIO_EXTICR1_EXTI3 (0xF << 12)
+#define AFIO_EXTICR1_EXTI3_PA (0x0 << 12)
+#define AFIO_EXTICR1_EXTI3_PB (0x1 << 12)
+#define AFIO_EXTICR1_EXTI3_PC (0x2 << 12)
+#define AFIO_EXTICR1_EXTI3_PD (0x3 << 12)
+#define AFIO_EXTICR1_EXTI3_PE (0x4 << 12)
+#define AFIO_EXTICR1_EXTI3_PF (0x5 << 12)
+#define AFIO_EXTICR1_EXTI3_PG (0x6 << 12)
+#define AFIO_EXTICR1_EXTI2 (0xF << 8)
+#define AFIO_EXTICR1_EXTI2_PA (0x0 << 8)
+#define AFIO_EXTICR1_EXTI2_PB (0x1 << 8)
+#define AFIO_EXTICR1_EXTI2_PC (0x2 << 8)
+#define AFIO_EXTICR1_EXTI2_PD (0x3 << 8)
+#define AFIO_EXTICR1_EXTI2_PE (0x4 << 8)
+#define AFIO_EXTICR1_EXTI2_PF (0x5 << 8)
+#define AFIO_EXTICR1_EXTI2_PG (0x6 << 8)
+#define AFIO_EXTICR1_EXTI1 (0xF << 4)
+#define AFIO_EXTICR1_EXTI1_PA (0x0 << 4)
+#define AFIO_EXTICR1_EXTI1_PB (0x1 << 4)
+#define AFIO_EXTICR1_EXTI1_PC (0x2 << 4)
+#define AFIO_EXTICR1_EXTI1_PD (0x3 << 4)
+#define AFIO_EXTICR1_EXTI1_PE (0x4 << 4)
+#define AFIO_EXTICR1_EXTI1_PF (0x5 << 4)
+#define AFIO_EXTICR1_EXTI1_PG (0x6 << 4)
+#define AFIO_EXTICR1_EXTI0 0xF
+#define AFIO_EXTICR1_EXTI0_PA 0x0
+#define AFIO_EXTICR1_EXTI0_PB 0x1
+#define AFIO_EXTICR1_EXTI0_PC 0x2
+#define AFIO_EXTICR1_EXTI0_PD 0x3
+#define AFIO_EXTICR1_EXTI0_PE 0x4
+#define AFIO_EXTICR1_EXTI0_PF 0x5
+#define AFIO_EXTICR1_EXTI0_PG 0x6
+
+/* External interrupt configuration register 2 */
+
+#define AFIO_EXTICR2_EXTI7 (0xF << 12)
+#define AFIO_EXTICR2_EXTI7_PA (0x0 << 12)
+#define AFIO_EXTICR2_EXTI7_PB (0x1 << 12)
+#define AFIO_EXTICR2_EXTI7_PC (0x2 << 12)
+#define AFIO_EXTICR2_EXTI7_PD (0x3 << 12)
+#define AFIO_EXTICR2_EXTI7_PE (0x4 << 12)
+#define AFIO_EXTICR2_EXTI7_PF (0x5 << 12)
+#define AFIO_EXTICR2_EXTI7_PG (0x6 << 12)
+#define AFIO_EXTICR2_EXTI6 (0xF << 8)
+#define AFIO_EXTICR2_EXTI6_PA (0x0 << 8)
+#define AFIO_EXTICR2_EXTI6_PB (0x1 << 8)
+#define AFIO_EXTICR2_EXTI6_PC (0x2 << 8)
+#define AFIO_EXTICR2_EXTI6_PD (0x3 << 8)
+#define AFIO_EXTICR2_EXTI6_PE (0x4 << 8)
+#define AFIO_EXTICR2_EXTI6_PF (0x5 << 8)
+#define AFIO_EXTICR2_EXTI6_PG (0x6 << 8)
+#define AFIO_EXTICR2_EXTI5 (0xF << 4)
+#define AFIO_EXTICR2_EXTI5_PA (0x0 << 4)
+#define AFIO_EXTICR2_EXTI5_PB (0x1 << 4)
+#define AFIO_EXTICR2_EXTI5_PC (0x2 << 4)
+#define AFIO_EXTICR2_EXTI5_PD (0x3 << 4)
+#define AFIO_EXTICR2_EXTI5_PE (0x4 << 4)
+#define AFIO_EXTICR2_EXTI5_PF (0x5 << 4)
+#define AFIO_EXTICR2_EXTI5_PG (0x6 << 4)
+#define AFIO_EXTICR2_EXTI4 0xF
+#define AFIO_EXTICR2_EXTI4_PA 0x0
+#define AFIO_EXTICR2_EXTI4_PB 0x1
+#define AFIO_EXTICR2_EXTI4_PC 0x2
+#define AFIO_EXTICR2_EXTI4_PD 0x3
+#define AFIO_EXTICR2_EXTI4_PE 0x4
+#define AFIO_EXTICR2_EXTI4_PF 0x5
+#define AFIO_EXTICR2_EXTI4_PG 0x6
+
+/* AF remap and debug I/O configuration register 2 */
+
+#define AFIO_MAPR2_FSMC_NADV (1U << 10)
+#define AFIO_MAPR2_TIM14_REMAP (1U << 9)
+#define AFIO_MAPR2_TIM13_REMAP (1U << 8)
+#define AFIO_MAPR2_TIM11_REMAP (1U << 7)
+#define AFIO_MAPR2_TIM10_REMAP (1U << 6)
+#define AFIO_MAPR2_TIM9_REMAP (1U << 5)
+
+/*
+ * AFIO convenience routines
+ */
+
+void afio_init(void);
+
+/* HACK: Use upper bit to denote MAPR2, Bit 31 is reserved and
+ * not used in either MAPR or MAPR2 */
+#define AFIO_REMAP_USE_MAPR2 (1U << 31)
+
+/**
+ * @brief Available peripheral remaps.
+ * @see afio_remap()
+ */
+typedef enum afio_remap_peripheral {
+ /** ADC 2 external trigger regular conversion remapping */
+ AFIO_REMAP_ADC2_ETRGREG = AFIO_MAPR_ADC2_ETRGREG_REMAP,
+ /** ADC 2 external trigger injected conversion remapping */
+ AFIO_REMAP_ADC2_ETRGINJ = AFIO_MAPR_ADC2_ETRGINJ_REMAP,
+ /** ADC 1 external trigger regular conversion remapping */
+ AFIO_REMAP_ADC1_ETRGREG = AFIO_MAPR_ADC1_ETRGREG_REMAP,
+ /** ADC 1 external trigger injected conversion remapping */
+ AFIO_REMAP_ADC1_ETRGINJ = AFIO_MAPR_ADC1_ETRGINJ_REMAP,
+ /** Timer 5 channel 4 internal remapping */
+ AFIO_REMAP_TIM5CH4_I = AFIO_MAPR_TIM5CH4_IREMAP,
+ /** Port D0/Port D1 mapping on OSC_IN/OSC_OUT */
+ AFIO_REMAP_PD01 = AFIO_MAPR_PD01_REMAP,
+ /** CAN alternate function remapping 1 (RX on PB8, TX on PB9) */
+ AFIO_REMAP_CAN_1 = AFIO_MAPR_CAN_REMAP_PB8_PB9,
+ /** CAN alternate function remapping 2 (RX on PD0, TX on PD1) */
+ AFIO_REMAP_CAN_2 = AFIO_MAPR_CAN_REMAP_PD0_PD1,
+ /** Timer 4 remapping */
+ AFIO_REMAP_TIM4 = AFIO_MAPR_TIM4_REMAP,
+ /** Timer 3 partial remapping */
+ AFIO_REMAP_TIM3_PARTIAL = AFIO_MAPR_TIM3_REMAP_PARTIAL,
+ /** Timer 3 full remapping */
+ AFIO_REMAP_TIM3_FULL = AFIO_MAPR_TIM3_REMAP_FULL,
+ /**
+ * Timer 2 partial remapping 1 (CH1 and ETR on PA15, CH2 on PB3,
+ * CH3 on PA2, CH4 on PA3) */
+ AFIO_REMAP_TIM2_PARTIAL_1 = AFIO_MAPR_TIM2_REMAP_PA15_PB3_PA2_PA3,
+ /**
+ * Timer 2 partial remapping 2 (CH1 and ETR on PA0, CH2 on PA1,
+ * CH3 on PB10, CH4 on PB11) */
+ AFIO_REMAP_TIM2_PARTIAL_2 = AFIO_MAPR_TIM2_REMAP_PA0_PA1_PB10_PB11,
+ /** Timer 2 full remapping */
+ AFIO_REMAP_TIM2_FULL = AFIO_MAPR_TIM2_REMAP_FULL,
+ /** USART 2 remapping */
+ AFIO_REMAP_USART2 = AFIO_MAPR_USART2_REMAP,
+ /** USART 1 remapping */
+ AFIO_REMAP_USART1 = AFIO_MAPR_USART1_REMAP,
+ /** I2C 1 remapping */
+ AFIO_REMAP_I2C1 = AFIO_MAPR_I2C1_REMAP,
+ /** SPI 1 remapping */
+ AFIO_REMAP_SPI1 = AFIO_MAPR_SPI1_REMAP,
+ /** NADV signal not connected */
+ AFIO_REMAP_FSMC_NADV = AFIO_MAPR2_FSMC_NADV | AFIO_REMAP_USE_MAPR2,
+ /** Timer 14 remapping */
+ AFIO_REMAP_TIM14 = AFIO_MAPR2_TIM14_REMAP | AFIO_REMAP_USE_MAPR2,
+ /** Timer 13 remapping */
+ AFIO_REMAP_TIM13 = AFIO_MAPR2_TIM13_REMAP | AFIO_REMAP_USE_MAPR2,
+ /** Timer 11 remapping */
+ AFIO_REMAP_TIM11 = AFIO_MAPR2_TIM11_REMAP | AFIO_REMAP_USE_MAPR2,
+ /** Timer 10 remapping */
+ AFIO_REMAP_TIM10 = AFIO_MAPR2_TIM10_REMAP | AFIO_REMAP_USE_MAPR2,
+ /** Timer 9 remapping */
+ AFIO_REMAP_TIM9 = AFIO_MAPR2_TIM9_REMAP | AFIO_REMAP_USE_MAPR2,
+} afio_remap_peripheral;
+
+void afio_remap(afio_remap_peripheral p);
+
+/**
+ * @brief Debug port configuration
+ *
+ * Used to configure the behavior of JTAG and Serial Wire (SW) debug
+ * ports and their associated GPIO pins.
+ *
+ * @see afio_cfg_debug_ports()
+ */
+typedef enum afio_debug_cfg {
+ /** Full Serial Wire and JTAG debug */
+ AFIO_DEBUG_FULL_SWJ = AFIO_MAPR_SWJ_CFG_FULL_SWJ,
+ /** Full Serial Wire and JTAG, but no NJTRST. */
+ AFIO_DEBUG_FULL_SWJ_NO_NJRST = AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_NJRST,
+ /** Serial Wire debug only (JTAG-DP disabled, SW-DP enabled) */
+ AFIO_DEBUG_SW_ONLY = AFIO_MAPR_SWJ_CFG_NO_JTAG_SW,
+ /** No debug; all JTAG and SW pins are free for use as GPIOs. */
+ AFIO_DEBUG_NONE = AFIO_MAPR_SWJ_CFG_NO_JTAG_NO_SW,
+} afio_debug_cfg;
+
+/**
+ * @brief Enable or disable the JTAG and SW debug ports.
+ * @param config Desired debug port configuration
+ * @see afio_debug_cfg
+ */
+static inline void afio_cfg_debug_ports(afio_debug_cfg config) {
+ __io uint32 *mapr = &AFIO_BASE->MAPR;
+ *mapr = (*mapr & ~AFIO_MAPR_SWJ_CFG) | config;
+}
+
+/*
+ * Deprecated bits
+ */
+
+/**
+ * @brief Deprecated. Use exti_cfg instead.
+ *
+ * In previous versions of libmaple, exti_attach_interrupt() took an
+ * afio_exti_port argument; afio_exti_port was also a member of struct
+ * gpio_dev. This isn't portable, so we now use exti_cfg
+ * instead. This typedef (and the macros AFIO_EXTI_PA, ...,
+ * AFIO_EXTI_PG) exist to preserve backwards compatibility.
+ */
+typedef exti_cfg afio_exti_port;
+
+/** Deprecated. Use EXTI_PA instead. */
+#define AFIO_EXTI_PA EXTI_PA
+/** Deprecated. Use EXTI_PB instead. */
+#define AFIO_EXTI_PB EXTI_PB
+/** Deprecated. Use EXTI_PC instead. */
+#define AFIO_EXTI_PC EXTI_PC
+/** Deprecated. Use EXTI_PD instead. */
+#define AFIO_EXTI_PD EXTI_PD
+/** Deprecated. Use EXTI_PE instead. */
+#define AFIO_EXTI_PE EXTI_PE
+/** Deprecated. Use EXTI_PF instead. */
+#define AFIO_EXTI_PF EXTI_PF
+/** Deprecated. Use EXTI_PG instead. */
+#define AFIO_EXTI_PG EXTI_PG
+
+/**
+ * @brief Deprecated. Use exti_num instead.
+ *
+ * In previous versions of libmaple, exti_attach_interrupt() took an
+ * afio_exti_num argument. This isn't portable, so we use exti_num
+ * instead. This typedef (and the macros AFIO_EXTI_0, ...,
+ * AFIO_EXTI_15) exist to preserve backwards compatibility.
+ */
+typedef exti_num afio_exti_num;
+
+/** Deprecated. Use EXTI0 instead. */
+#define AFIO_EXTI_0 EXTI0
+/** Deprecated. Use EXTI1 instead. */
+#define AFIO_EXTI_1 EXTI1
+/** Deprecated. Use EXTI2 instead. */
+#define AFIO_EXTI_2 EXTI2
+/** Deprecated. Use EXTI3 instead. */
+#define AFIO_EXTI_3 EXTI3
+/** Deprecated. Use EXTI4 instead. */
+#define AFIO_EXTI_4 EXTI4
+/** Deprecated. Use EXTI5 instead. */
+#define AFIO_EXTI_5 EXTI5
+/** Deprecated. Use EXTI6 instead. */
+#define AFIO_EXTI_6 EXTI6
+/** Deprecated. Use EXTI7 instead. */
+#define AFIO_EXTI_7 EXTI7
+/** Deprecated. Use EXTI8 instead. */
+#define AFIO_EXTI_8 EXTI8
+/** Deprecated. Use EXTI9 instead. */
+#define AFIO_EXTI_9 EXTI9
+/** Deprecated. Use EXTI10 instead. */
+#define AFIO_EXTI_10 EXTI10
+/** Deprecated. Use EXTI11 instead. */
+#define AFIO_EXTI_11 EXTI11
+/** Deprecated. Use EXTI12 instead. */
+#define AFIO_EXTI_12 EXTI12
+/** Deprecated. Use EXTI13 instead. */
+#define AFIO_EXTI_13 EXTI13
+/** Deprecated. Use EXTI14 instead. */
+#define AFIO_EXTI_14 EXTI14
+/** Deprecated. Use EXTI15 instead. */
+#define AFIO_EXTI_15 EXTI15
+
+/**
+ * @brief Deprecated. Use exti_select(exti, port) instead.
+ */
+static __always_inline void afio_exti_select(exti_num exti, exti_cfg port) {
+ exti_select(exti, port);
+}
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/libmaple/stm32f1/include/series/i2c.h b/libmaple/stm32f1/include/series/i2c.h
new file mode 100644
index 0000000..f407955
--- /dev/null
+++ b/libmaple/stm32f1/include/series/i2c.h
@@ -0,0 +1,85 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 Perry Hung (from <libmaple/i2c.h>).
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/include/series/i2c.h
+ * @brief STM32F1 I2C
+ */
+
+#ifndef _LIBMAPLE_STM32F1_I2C_H_
+#define _LIBMAPLE_STM32F1_I2C_H_
+
+#include <libmaple/i2c_common.h>
+#include <libmaple/gpio.h>
+#include <libmaple/stm32.h>
+
+/*
+ * Register maps
+ */
+
+struct i2c_reg_map;
+
+/** STM32F1 I2C1 register map base pointer */
+#define I2C1_BASE ((struct i2c_reg_map*)0x40005400)
+/** STM32F1 I2C2 register map base pointer */
+#define I2C2_BASE ((struct i2c_reg_map*)0x40005800)
+
+/*
+ * Devices
+ */
+
+extern i2c_dev* const I2C1;
+extern i2c_dev* const I2C2;
+
+/*
+ * For internal use
+ */
+
+static inline uint32 _i2c_bus_clk(i2c_dev *dev) {
+ /* Both I2C peripherals are on APB1 */
+ return STM32_PCLK1 / (1000 * 1000);
+}
+
+#define _I2C_HAVE_IRQ_FIXUP 1
+void _i2c_irq_priority_fixup(i2c_dev *dev);
+
+/*
+ * Deprecated functionality
+ */
+
+/* Flag to use alternate pin mapping in i2c_master_enable(). */
+#define _I2C_HAVE_DEPRECATED_I2C_REMAP 1
+#define I2C_REMAP 0x4
+static inline void _i2c_handle_remap(i2c_dev *dev, uint32 flags) {
+ if ((dev == I2C1) && (flags & I2C_REMAP)) {
+ afio_remap(AFIO_REMAP_I2C1);
+ I2C1->sda_pin = 9;
+ I2C1->scl_pin = 8;
+ }
+}
+
+#endif /* _LIBMAPLE_STM32F1_I2C_H_ */
diff --git a/libmaple/stm32f1/include/series/nvic.h b/libmaple/stm32f1/include/series/nvic.h
new file mode 100644
index 0000000..cdac737
--- /dev/null
+++ b/libmaple/stm32f1/include/series/nvic.h
@@ -0,0 +1,173 @@
+/******************************************************************************
+ * 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 libmaple/stm32f1/include/series/nvic.h
+ * @brief STM32F1 Nested Vectored Interrupt Controller (NVIC) support.
+ */
+
+#ifndef _LIBMAPLE_STM32F1_NVIC_H_
+#define _LIBMAPLE_STM32F1_NVIC_H_
+
+#ifdef __cplusplus
+extern "C"{
+#endif
+
+#include <libmaple/libmaple_types.h>
+#include <libmaple/stm32.h>
+
+/**
+ * @brief STM32F1 interrupt vector table interrupt numbers.
+ * @see <libmaple/scb.h>
+ */
+typedef enum nvic_irq_num {
+ NVIC_NMI = -14, /**< Non-maskable interrupt */
+ NVIC_HARDFAULT = -13, /**< Hard fault (all class of fault) */
+ NVIC_MEM_MANAGE = -12, /**< Memory management */
+ NVIC_BUS_FAULT = -11, /**< Bus fault: prefetch fault, memory
+ access fault. */
+ NVIC_USAGE_FAULT = -10, /**< Usage fault: Undefined instruction or
+ illegal state. */
+ NVIC_SVC = -5, /**< System service call via SWI insruction */
+ NVIC_DEBUG_MON = -4, /**< Debug monitor */
+ NVIC_PEND_SVC = -2, /**< Pendable request for system service */
+ NVIC_SYSTICK = -1, /**< System tick timer */
+ NVIC_WWDG = 0, /**< Window watchdog interrupt */
+ NVIC_PVD = 1, /**< PVD through EXTI line detection */
+ NVIC_TAMPER = 2, /**< Tamper */
+ NVIC_RTC = 3, /**< Real-time clock */
+ NVIC_FLASH = 4, /**< Flash */
+ NVIC_RCC = 5, /**< Reset and clock control */
+ NVIC_EXTI0 = 6, /**< EXTI line 0 */
+ NVIC_EXTI1 = 7, /**< EXTI line 1 */
+ NVIC_EXTI2 = 8, /**< EXTI line 2 */
+ NVIC_EXTI3 = 9, /**< EXTI line 3 */
+ NVIC_EXTI4 = 10, /**< EXTI line 4 */
+ NVIC_DMA_CH1 = 11, /**< DMA1 channel 1 */
+ NVIC_DMA_CH2 = 12, /**< DMA1 channel 2 */
+ NVIC_DMA_CH3 = 13, /**< DMA1 channel 3 */
+ NVIC_DMA_CH4 = 14, /**< DMA1 channel 4 */
+ NVIC_DMA_CH5 = 15, /**< DMA1 channel 5 */
+ NVIC_DMA_CH6 = 16, /**< DMA1 channel 6 */
+ NVIC_DMA_CH7 = 17, /**< DMA1 channel 7 */
+ NVIC_ADC_1_2 = 18, /**< ADC1 and ADC2 */
+ NVIC_USB_HP_CAN_TX = 19, /**< USB high priority or CAN TX */
+ NVIC_USB_LP_CAN_RX0 = 20, /**< USB low priority or CAN RX0 */
+ NVIC_CAN_RX1 = 21, /**< CAN RX1 */
+ NVIC_CAN_SCE = 22, /**< CAN SCE */
+ NVIC_EXTI_9_5 = 23, /**< EXTI line [9:5] */
+ NVIC_TIMER1_BRK_TIMER9 = 24, /**< Timer 1 break, Timer 9. */
+ NVIC_TIMER1_UP_TIMER10 = 25, /**< Timer 1 update, Timer 10. */
+ NVIC_TIMER1_TRG_COM_TIMER11 = 26, /**<
+ * Timer 1 trigger and commutation,
+ * Timer 11. */
+ NVIC_TIMER1_CC = 27, /**< Timer 1 capture/compare */
+ NVIC_TIMER2 = 28, /**< Timer 2 */
+ NVIC_TIMER3 = 29, /**< Timer 3 */
+ NVIC_TIMER4 = 30, /**< Timer 4 */
+ NVIC_I2C1_EV = 31, /**< I2C1 event */
+ NVIC_I2C1_ER = 32, /**< I2C1 error */
+ NVIC_I2C2_EV = 33, /**< I2C2 event */
+ NVIC_I2C2_ER = 34, /**< I2C2 error */
+ NVIC_SPI1 = 35, /**< SPI1 */
+ NVIC_SPI2 = 36, /**< SPI2 */
+ NVIC_USART1 = 37, /**< USART1 */
+ NVIC_USART2 = 38, /**< USART2 */
+ NVIC_USART3 = 39, /**< USART3 */
+ NVIC_EXTI_15_10 = 40, /**< EXTI line [15:10] */
+ NVIC_RTCALARM = 41, /**< RTC alarm through EXTI line */
+ NVIC_USBWAKEUP = 42, /**< USB wakeup from suspend through
+ EXTI line */
+ NVIC_TIMER8_BRK_TIMER12 = 43, /**< Timer 8 break, timer 12 */
+ NVIC_TIMER8_UP_TIMER13 = 44, /**< Timer 8 update, timer 13 */
+ NVIC_TIMER8_TRG_COM_TIMER14 = 45, /**<
+ * Timer 8 trigger and commutation,
+ * Timer 14. */
+ NVIC_TIMER8_CC = 46, /**< Timer 8 capture/compare */
+ NVIC_ADC3 = 47, /**< ADC3 */
+ NVIC_FSMC = 48, /**< FSMC */
+ NVIC_SDIO = 49, /**< SDIO */
+ NVIC_TIMER5 = 50, /**< Timer 5 */
+ NVIC_SPI3 = 51, /**< SPI3 */
+ NVIC_UART4 = 52, /**< UART4 */
+ NVIC_UART5 = 53, /**< UART5 */
+ NVIC_TIMER6 = 54, /**< Timer 6 */
+ NVIC_TIMER7 = 55, /**< Timer 7 */
+ NVIC_DMA2_CH1 = 56, /**< DMA2 channel 1 */
+ NVIC_DMA2_CH2 = 57, /**< DMA2 channel 2 */
+ NVIC_DMA2_CH3 = 58, /**< DMA2 channel 3 */
+ NVIC_DMA2_CH_4_5 = 59, /**< DMA2 channels 4 and 5 */
+
+ /* Old enumerators kept around for backwards compatibility: */
+ NVIC_TIMER1_BRK =
+ NVIC_TIMER1_BRK_TIMER9, /**< @brief (Deprecated) Timer 1 break
+ *
+ * For backwards compatibility only.
+ * Use NVIC_TIMER1_BRK_TIMER9 instead. */
+ NVIC_TIMER1_UP =
+ NVIC_TIMER1_UP_TIMER10, /**< @brief (Deprecated) Timer 1 update.
+ *
+ * For backwards compatibility only.
+ * Use NVIC_TIMER1_UP_TIMER10 instead. */
+ NVIC_TIMER1_TRG_COM =
+ NVIC_TIMER1_TRG_COM_TIMER11, /**< @brief (deprecated) Timer 1 trigger
+ * and commutation.
+ *
+ * For backwards compatibility only.
+ * Use NVIC_TIMER1_TRG_COM_TIMER11
+ * instead. */
+ NVIC_TIMER8_BRK =
+ NVIC_TIMER8_BRK_TIMER12, /**< @brief (deprecated) Timer 8 break
+ *
+ * For backwards compatibility only.
+ * Use NVIC_TIMER8_BRK_TIMER12 instead. */
+ NVIC_TIMER8_UP =
+ NVIC_TIMER8_UP_TIMER13, /**< @brief (deprecated) Timer 8 update
+ * For backwards compatibility only.
+ * Use NVIC_TIMER8_UP_TIMER13 instead. */
+ NVIC_TIMER8_TRG_COM =
+ NVIC_TIMER8_TRG_COM_TIMER14, /**< @brief (deprecated) Timer 8 trigger
+ * and commutation.
+ * For backwards compatibility only.
+ * Use NVIC_TIMER8_TRG_COM_TIMER14
+ * instead. */
+} nvic_irq_num;
+
+static inline void nvic_irq_disable_all(void) {
+ /* Even low-density devices have over 32 interrupt lines. */
+ NVIC_BASE->ICER[0] = 0xFFFFFFFF;
+ NVIC_BASE->ICER[1] = 0xFFFFFFFF;
+#if STM32_NR_INTERRUPTS > 64
+ /* Only some have over 64; e.g. connectivity line MCUs. */
+ NVIC_BASE->ICER[2] = 0xFFFFFFFF;
+#endif
+}
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/libmaple/stm32f1/include/series/pwr.h b/libmaple/stm32f1/include/series/pwr.h
new file mode 100644
index 0000000..e143a8c
--- /dev/null
+++ b/libmaple/stm32f1/include/series/pwr.h
@@ -0,0 +1,52 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/include/series/pwr.h
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief STM32F1 Power control (PWR) support.
+ */
+
+#ifndef _LIBMAPLE_STM32F1_PWR_H_
+#define _LIBMAPLE_STM32F1_PWR_H_
+
+/*
+ * Register bit definitions
+ */
+
+/* Control register */
+
+/* PVD level selection */
+#define PWR_CR_PLS_2_2V (0x0 << 5)
+#define PWR_CR_PLS_2_3V (0x1 << 5)
+#define PWR_CR_PLS_2_4V (0x2 << 5)
+#define PWR_CR_PLS_2_5V (0x3 << 5)
+#define PWR_CR_PLS_2_6V (0x4 << 5)
+#define PWR_CR_PLS_2_7V (0x5 << 5)
+#define PWR_CR_PLS_2_8V (0x6 << 5)
+#define PWR_CR_PLS_2_9V (0x7 << 5)
+
+#endif
diff --git a/libmaple/stm32f1/include/series/rcc.h b/libmaple/stm32f1/include/series/rcc.h
new file mode 100644
index 0000000..225ca49
--- /dev/null
+++ b/libmaple/stm32f1/include/series/rcc.h
@@ -0,0 +1,599 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2011 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/include/series/rcc.h
+ * @brief STM32F1 reset and clock control (RCC) support.
+ */
+
+#ifndef _LIBMAPLE_STM32F1_RCC_H_
+#define _LIBMAPLE_STM32F1_RCC_H_
+
+#ifdef __cplusplus
+extern "C"{
+#endif
+
+#include <libmaple/libmaple_types.h>
+
+/*
+ * Register map
+ */
+
+/** STM32F1 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;
+
+#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 (1U << RCC_CR_PLLRDY_BIT)
+#define RCC_CR_PLLON (1U << RCC_CR_PLLON_BIT)
+#define RCC_CR_CSSON (1U << RCC_CR_CSSON_BIT)
+#define RCC_CR_HSEBYP (1U << RCC_CR_HSEBYP_BIT)
+#define RCC_CR_HSERDY (1U << RCC_CR_HSERDY_BIT)
+#define RCC_CR_HSEON (1U << RCC_CR_HSEON_BIT)
+#define RCC_CR_HSICAL (0xFF << 8)
+#define RCC_CR_HSITRIM (0x1F << 3)
+#define RCC_CR_HSIRDY (1U << RCC_CR_HSIRDY_BIT)
+#define RCC_CR_HSION (1U << 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 (1U << RCC_CFGR_USBPRE_BIT)
+#define RCC_CFGR_PLLMUL (0xF << 18)
+#define RCC_CFGR_PLLXTPRE (1U << RCC_CFGR_PLLXTPRE_BIT)
+#define RCC_CFGR_PLLSRC (1U << 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 (1U << RCC_CIR_CSSC_BIT)
+#define RCC_CIR_PLLRDYC (1U << RCC_CIR_PLLRDYC_BIT)
+#define RCC_CIR_HSERDYC (1U << RCC_CIR_HSERDYC_BIT)
+#define RCC_CIR_HSIRDYC (1U << RCC_CIR_HSIRDYC_BIT)
+#define RCC_CIR_LSERDYC (1U << RCC_CIR_LSERDYC_BIT)
+#define RCC_CIR_LSIRDYC (1U << RCC_CIR_LSIRDYC_BIT)
+#define RCC_CIR_PLLRDYIE (1U << RCC_CIR_PLLRDYIE_BIT)
+#define RCC_CIR_HSERDYIE (1U << RCC_CIR_HSERDYIE_BIT)
+#define RCC_CIR_HSIRDYIE (1U << RCC_CIR_HSIRDYIE_BIT)
+#define RCC_CIR_LSERDYIE (1U << RCC_CIR_LSERDYIE_BIT)
+#define RCC_CIR_LSIRDYIE (1U << RCC_CIR_LSIRDYIE_BIT)
+#define RCC_CIR_CSSF (1U << RCC_CIR_CSSF_BIT)
+#define RCC_CIR_PLLRDYF (1U << RCC_CIR_PLLRDYF_BIT)
+#define RCC_CIR_HSERDYF (1U << RCC_CIR_HSERDYF_BIT)
+#define RCC_CIR_HSIRDYF (1U << RCC_CIR_HSIRDYF_BIT)
+#define RCC_CIR_LSERDYF (1U << RCC_CIR_LSERDYF_BIT)
+#define RCC_CIR_LSIRDYF (1U << 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 (1U << RCC_APB2RSTR_TIM11RST_BIT)
+#define RCC_APB2RSTR_TIM10RST (1U << RCC_APB2RSTR_TIM10RST_BIT)
+#define RCC_APB2RSTR_TIM9RST (1U << RCC_APB2RSTR_TIM9RST_BIT)
+#define RCC_APB2RSTR_ADC3RST (1U << RCC_APB2RSTR_ADC3RST_BIT)
+#define RCC_APB2RSTR_USART1RST (1U << RCC_APB2RSTR_USART1RST_BIT)
+#define RCC_APB2RSTR_TIM8RST (1U << RCC_APB2RSTR_TIM8RST_BIT)
+#define RCC_APB2RSTR_SPI1RST (1U << RCC_APB2RSTR_SPI1RST_BIT)
+#define RCC_APB2RSTR_TIM1RST (1U << RCC_APB2RSTR_TIM1RST_BIT)
+#define RCC_APB2RSTR_ADC2RST (1U << RCC_APB2RSTR_ADC2RST_BIT)
+#define RCC_APB2RSTR_ADC1RST (1U << RCC_APB2RSTR_ADC1RST_BIT)
+#define RCC_APB2RSTR_IOPGRST (1U << RCC_APB2RSTR_IOPGRST_BIT)
+#define RCC_APB2RSTR_IOPFRST (1U << RCC_APB2RSTR_IOPFRST_BIT)
+#define RCC_APB2RSTR_IOPERST (1U << RCC_APB2RSTR_IOPERST_BIT)
+#define RCC_APB2RSTR_IOPDRST (1U << RCC_APB2RSTR_IOPDRST_BIT)
+#define RCC_APB2RSTR_IOPCRST (1U << RCC_APB2RSTR_IOPCRST_BIT)
+#define RCC_APB2RSTR_IOPBRST (1U << RCC_APB2RSTR_IOPBRST_BIT)
+#define RCC_APB2RSTR_IOPARST (1U << RCC_APB2RSTR_IOPARST_BIT)
+#define RCC_APB2RSTR_AFIORST (1U << 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 (1U << RCC_APB1RSTR_DACRST_BIT)
+#define RCC_APB1RSTR_PWRRST (1U << RCC_APB1RSTR_PWRRST_BIT)
+#define RCC_APB1RSTR_BKPRST (1U << RCC_APB1RSTR_BKPRST_BIT)
+#define RCC_APB1RSTR_CANRST (1U << RCC_APB1RSTR_CANRST_BIT)
+#define RCC_APB1RSTR_USBRST (1U << RCC_APB1RSTR_USBRST_BIT)
+#define RCC_APB1RSTR_I2C2RST (1U << RCC_APB1RSTR_I2C2RST_BIT)
+#define RCC_APB1RSTR_I2C1RST (1U << RCC_APB1RSTR_I2C1RST_BIT)
+#define RCC_APB1RSTR_UART5RST (1U << RCC_APB1RSTR_UART5RST_BIT)
+#define RCC_APB1RSTR_UART4RST (1U << RCC_APB1RSTR_UART4RST_BIT)
+#define RCC_APB1RSTR_USART3RST (1U << RCC_APB1RSTR_USART3RST_BIT)
+#define RCC_APB1RSTR_USART2RST (1U << RCC_APB1RSTR_USART2RST_BIT)
+#define RCC_APB1RSTR_SPI3RST (1U << RCC_APB1RSTR_SPI3RST_BIT)
+#define RCC_APB1RSTR_SPI2RST (1U << RCC_APB1RSTR_SPI2RST_BIT)
+#define RCC_APB1RSTR_WWDRST (1U << RCC_APB1RSTR_WWDRST_BIT)
+#define RCC_APB1RSTR_TIM14RST (1U << RCC_APB1RSTR_TIM14RST_BIT)
+#define RCC_APB1RSTR_TIM13RST (1U << RCC_APB1RSTR_TIM13RST_BIT)
+#define RCC_APB1RSTR_TIM12RST (1U << RCC_APB1RSTR_TIM12RST_BIT)
+#define RCC_APB1RSTR_TIM7RST (1U << RCC_APB1RSTR_TIM7RST_BIT)
+#define RCC_APB1RSTR_TIM6RST (1U << RCC_APB1RSTR_TIM6RST_BIT)
+#define RCC_APB1RSTR_TIM5RST (1U << RCC_APB1RSTR_TIM5RST_BIT)
+#define RCC_APB1RSTR_TIM4RST (1U << RCC_APB1RSTR_TIM4RST_BIT)
+#define RCC_APB1RSTR_TIM3RST (1U << RCC_APB1RSTR_TIM3RST_BIT)
+#define RCC_APB1RSTR_TIM2RST (1U << 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 (1U << RCC_AHBENR_SDIOEN_BIT)
+#define RCC_AHBENR_FSMCEN (1U << RCC_AHBENR_FSMCEN_BIT)
+#define RCC_AHBENR_CRCEN (1U << RCC_AHBENR_CRCEN_BIT)
+#define RCC_AHBENR_FLITFEN (1U << RCC_AHBENR_FLITFEN_BIT)
+#define RCC_AHBENR_SRAMEN (1U << RCC_AHBENR_SRAMEN_BIT)
+#define RCC_AHBENR_DMA2EN (1U << RCC_AHBENR_DMA2EN_BIT)
+#define RCC_AHBENR_DMA1EN (1U << 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 (1U << RCC_APB2ENR_TIM11EN_BIT)
+#define RCC_APB2ENR_TIM10EN (1U << RCC_APB2ENR_TIM10EN_BIT)
+#define RCC_APB2ENR_TIM9EN (1U << RCC_APB2ENR_TIM9EN_BIT)
+#define RCC_APB2ENR_ADC3EN (1U << RCC_APB2ENR_ADC3EN_BIT)
+#define RCC_APB2ENR_USART1EN (1U << RCC_APB2ENR_USART1EN_BIT)
+#define RCC_APB2ENR_TIM8EN (1U << RCC_APB2ENR_TIM8EN_BIT)
+#define RCC_APB2ENR_SPI1EN (1U << RCC_APB2ENR_SPI1EN_BIT)
+#define RCC_APB2ENR_TIM1EN (1U << RCC_APB2ENR_TIM1EN_BIT)
+#define RCC_APB2ENR_ADC2EN (1U << RCC_APB2ENR_ADC2EN_BIT)
+#define RCC_APB2ENR_ADC1EN (1U << RCC_APB2ENR_ADC1EN_BIT)
+#define RCC_APB2ENR_IOPGEN (1U << RCC_APB2ENR_IOPGEN_BIT)
+#define RCC_APB2ENR_IOPFEN (1U << RCC_APB2ENR_IOPFEN_BIT)
+#define RCC_APB2ENR_IOPEEN (1U << RCC_APB2ENR_IOPEEN_BIT)
+#define RCC_APB2ENR_IOPDEN (1U << RCC_APB2ENR_IOPDEN_BIT)
+#define RCC_APB2ENR_IOPCEN (1U << RCC_APB2ENR_IOPCEN_BIT)
+#define RCC_APB2ENR_IOPBEN (1U << RCC_APB2ENR_IOPBEN_BIT)
+#define RCC_APB2ENR_IOPAEN (1U << RCC_APB2ENR_IOPAEN_BIT)
+#define RCC_APB2ENR_AFIOEN (1U << 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 (1U << RCC_APB1ENR_DACEN_BIT)
+#define RCC_APB1ENR_PWREN (1U << RCC_APB1ENR_PWREN_BIT)
+#define RCC_APB1ENR_BKPEN (1U << RCC_APB1ENR_BKPEN_BIT)
+#define RCC_APB1ENR_CANEN (1U << RCC_APB1ENR_CANEN_BIT)
+#define RCC_APB1ENR_USBEN (1U << RCC_APB1ENR_USBEN_BIT)
+#define RCC_APB1ENR_I2C2EN (1U << RCC_APB1ENR_I2C2EN_BIT)
+#define RCC_APB1ENR_I2C1EN (1U << RCC_APB1ENR_I2C1EN_BIT)
+#define RCC_APB1ENR_UART5EN (1U << RCC_APB1ENR_UART5EN_BIT)
+#define RCC_APB1ENR_UART4EN (1U << RCC_APB1ENR_UART4EN_BIT)
+#define RCC_APB1ENR_USART3EN (1U << RCC_APB1ENR_USART3EN_BIT)
+#define RCC_APB1ENR_USART2EN (1U << RCC_APB1ENR_USART2EN_BIT)
+#define RCC_APB1ENR_SPI3EN (1U << RCC_APB1ENR_SPI3EN_BIT)
+#define RCC_APB1ENR_SPI2EN (1U << RCC_APB1ENR_SPI2EN_BIT)
+#define RCC_APB1ENR_WWDEN (1U << RCC_APB1ENR_WWDEN_BIT)
+#define RCC_APB1ENR_TIM14EN (1U << RCC_APB1ENR_TIM14EN_BIT)
+#define RCC_APB1ENR_TIM13EN (1U << RCC_APB1ENR_TIM13EN_BIT)
+#define RCC_APB1ENR_TIM12EN (1U << RCC_APB1ENR_TIM12EN_BIT)
+#define RCC_APB1ENR_TIM7EN (1U << RCC_APB1ENR_TIM7EN_BIT)
+#define RCC_APB1ENR_TIM6EN (1U << RCC_APB1ENR_TIM6EN_BIT)
+#define RCC_APB1ENR_TIM5EN (1U << RCC_APB1ENR_TIM5EN_BIT)
+#define RCC_APB1ENR_TIM4EN (1U << RCC_APB1ENR_TIM4EN_BIT)
+#define RCC_APB1ENR_TIM3EN (1U << RCC_APB1ENR_TIM3EN_BIT)
+#define RCC_APB1ENR_TIM2EN (1U << 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 (1U << RCC_BDCR_BDRST_BIT)
+#define RCC_BDCR_RTCEN (1U << RCC_BDCR_RTC_BIT)
+#define RCC_BDCR_RTCSEL (0x3 << 8)
+#define RCC_BDCR_RTCSEL_NONE (0x0 << 8)
+#define RCC_BDCR_RTCSEL_LSE (0x1 << 8)
+#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)
+#define RCC_BDCR_LSEON (1U << 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 (1U << RCC_CSR_LPWRRSTF_BIT)
+#define RCC_CSR_WWDGRSTF (1U << RCC_CSR_WWDGRSTF_BIT)
+#define RCC_CSR_IWDGRSTF (1U << RCC_CSR_IWDGRSTF_BIT)
+#define RCC_CSR_SFTRSTF (1U << RCC_CSR_SFTRSTF_BIT)
+#define RCC_CSR_PORRSTF (1U << RCC_CSR_PORRSTF_BIT)
+#define RCC_CSR_PINRSTF (1U << RCC_CSR_PINRSTF_BIT)
+#define RCC_CSR_RMVF (1U << RCC_CSR_RMVF_BIT)
+#define RCC_CSR_LSIRDY (1U << RCC_CSR_LSIRDY_BIT)
+#define RCC_CSR_LSION (1U << RCC_CSR_LSION_BIT)
+
+/*
+ * libmaple-mandated enumeration types.
+ */
+
+/**
+ * @brief STM32F1 rcc_clk_id.
+ */
+typedef enum rcc_clk_id {
+ RCC_ADC1,
+ RCC_ADC2,
+ RCC_ADC3,
+ RCC_AFIO,
+ RCC_BKP,
+ RCC_CRC,
+ RCC_DAC,
+ RCC_DMA1,
+ RCC_DMA2,
+ RCC_FLITF,
+ RCC_FSMC,
+ RCC_GPIOA,
+ RCC_GPIOB,
+ RCC_GPIOC,
+ RCC_GPIOD,
+ RCC_GPIOE,
+ RCC_GPIOF,
+ RCC_GPIOG,
+ RCC_I2C1,
+ RCC_I2C2,
+ RCC_PWR,
+ RCC_SDIO,
+ RCC_SPI1,
+ RCC_SPI2,
+ RCC_SPI3,
+ RCC_SRAM,
+ RCC_TIMER1,
+ RCC_TIMER2,
+ RCC_TIMER3,
+ RCC_TIMER4,
+ RCC_TIMER5,
+ RCC_TIMER6,
+ RCC_TIMER7,
+ RCC_TIMER8,
+ RCC_TIMER9,
+ RCC_TIMER10,
+ RCC_TIMER11,
+ RCC_TIMER12,
+ RCC_TIMER13,
+ RCC_TIMER14,
+ RCC_USART1,
+ RCC_USART2,
+ RCC_USART3,
+ RCC_UART4,
+ RCC_UART5,
+ RCC_USB,
+} rcc_clk_id;
+
+/**
+ * @brief STM32F1 PLL clock sources.
+ * @see rcc_configure_pll()
+ */
+typedef enum rcc_pllsrc {
+ RCC_PLLSRC_HSE = (0x1 << 16),
+ RCC_PLLSRC_HSI_DIV_2 = (0x0 << 16)
+} rcc_pllsrc;
+
+/**
+ * @brief STM32F1 clock domains.
+ * @see rcc_dev_clk()
+ */
+typedef enum rcc_clk_domain {
+ RCC_APB1,
+ RCC_APB2,
+ RCC_AHB
+} rcc_clk_domain;
+
+/**
+ * @brief STM32F1 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;
+
+/**
+ * @brief STM32F1 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;
+
+/**
+ * @brief STM32F1 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;
+
+/**
+ * @brief STM32F1 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;
+
+/**
+ * @brief STM32F1 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;
+
+/**
+ * @brief STM32F1 clock sources.
+ */
+typedef enum rcc_clk {
+ RCC_CLK_PLL = (uint16)((offsetof(struct rcc_reg_map, CR) << 8) |
+ RCC_CR_PLLON_BIT), /**< Main PLL, clocked by
+ HSI or HSE. */
+ RCC_CLK_HSE = (uint16)((offsetof(struct rcc_reg_map, CR) << 8) |
+ RCC_CR_HSEON_BIT), /**< High speed external. */
+ RCC_CLK_HSI = (uint16)((offsetof(struct rcc_reg_map, CR) << 8) |
+ RCC_CR_HSION_BIT), /**< High speed internal. */
+ RCC_CLK_LSE = (uint16)((offsetof(struct rcc_reg_map, BDCR) << 8) |
+ RCC_BDCR_LSEON_BIT), /**< Low-speed external
+ * (32.768 KHz). */
+ RCC_CLK_LSI = (uint16)((offsetof(struct rcc_reg_map, CSR) << 8) |
+ RCC_CSR_LSION_BIT), /**< Low-speed internal
+ * (approximately 32 KHz). */
+} rcc_clk;
+
+/**
+ * @brief STM32F1 PLL multipliers.
+ */
+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;
+
+/* FIXME [0.0.13] Just have data point to an rcc_pll_multiplier! */
+
+/**
+ * @brief STM32F1 PLL configuration values.
+ * Point to one of these with the "data" field in a struct rcc_pll_cfg.
+ * @see struct rcc_pll_cfg.
+ */
+typedef struct stm32f1_rcc_pll_data {
+ rcc_pll_multiplier pll_mul; /**< PLL multiplication factor. */
+} stm32f1_rcc_pll_data;
+
+/*
+ * Deprecated bits.
+ */
+
+/**
+ * @brief Deprecated; STM32F1 only.
+ *
+ * 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
+ */
+__deprecated
+void rcc_clk_init(rcc_sysclk_src sysclk_src,
+ rcc_pllsrc pll_src,
+ rcc_pll_multiplier pll_mul);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/libmaple/stm32f1/include/series/spi.h b/libmaple/stm32f1/include/series/spi.h
new file mode 100644
index 0000000..d288a0c
--- /dev/null
+++ b/libmaple/stm32f1/include/series/spi.h
@@ -0,0 +1,99 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
+ * 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 libmaple/stm32f1/include/series/spi.h
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief STM32F1 SPI/I2S series header.
+ */
+
+#ifndef _LIBMAPLE_STM32F1_SPI_H_
+#define _LIBMAPLE_STM32F1_SPI_H_
+
+#include <libmaple/libmaple_types.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/*
+ * Register map base pointers
+ */
+
+struct spi_reg_map;
+
+#define SPI1_BASE ((struct spi_reg_map*)0x40013000)
+#define SPI2_BASE ((struct spi_reg_map*)0x40003800)
+#define SPI3_BASE ((struct spi_reg_map*)0x40003C00)
+
+/*
+ * Device pointers
+ */
+
+struct spi_dev;
+
+extern struct spi_dev *SPI1;
+extern struct spi_dev *SPI2;
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+extern struct spi_dev *SPI3;
+#endif
+
+/*
+ * Routines
+ */
+
+/* spi_gpio_cfg(): Backwards compatibility shim to spi_config_gpios() */
+struct gpio_dev;
+extern void spi_config_gpios(struct spi_dev*, uint8,
+ struct gpio_dev*, uint8,
+ struct gpio_dev*, uint8, uint8, uint8);
+/**
+ * @brief Deprecated. Use spi_config_gpios() instead.
+ * @see spi_config_gpios()
+ */
+static __always_inline void spi_gpio_cfg(uint8 as_master,
+ struct gpio_dev *nss_dev,
+ uint8 nss_bit,
+ struct gpio_dev *comm_dev,
+ uint8 sck_bit,
+ uint8 miso_bit,
+ uint8 mosi_bit) {
+ /* We switched style globally to foo_config_gpios() and always
+ * taking a foo_dev* argument (that last bit is the important
+ * part) after this function was written.
+ *
+ * However, spi_config_gpios() just ignores the spi_dev* on F1, so
+ * we can still keep this around for older code. */
+ spi_config_gpios(NULL, as_master, nss_dev, nss_bit,
+ comm_dev, sck_bit, miso_bit, mosi_bit);
+}
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/libmaple/stm32f1/include/series/stm32.h b/libmaple/stm32f1/include/series/stm32.h
new file mode 100644
index 0000000..42a9744
--- /dev/null
+++ b/libmaple/stm32f1/include/series/stm32.h
@@ -0,0 +1,219 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010, 2011 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/include/series/stm32.h
+ * @brief STM32F1 chip- and series-specific definitions.
+ */
+
+#ifndef _LIBMAPLE_STM32F1_H_
+#define _LIBMAPLE_STM32F1_H_
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#define STM32_MCU_SERIES STM32_SERIES_F1
+
+/* The STM32F1 series is subdivided into "lines". libmaple currently
+ * officially supports STM32F103 performance line MCUs (see the
+ * MCU-specific value section below).
+ *
+ * You can use these F1 line defines if porting libmaple to support
+ * MCUs on other lines. */
+/** STM32F1 value line (STM32F100 MCUs). */
+#define STM32_F1_LINE_VALUE 0
+/** STM32F1 access line (STM32F101 MCUs). */
+#define STM32_F1_LINE_ACCESS 1
+/** STM32F1 USB access line (STM32F102 MCUs). */
+#define STM32_F1_LINE_USB_ACCESS 2
+/** STM32F1 performance line (STM32F103 MCUs). */
+#define STM32_F1_LINE_PERFORMANCE 3
+/** STM32F1 connectivity line (STM32F105/F107 MCUs). */
+#define STM32_F1_LINE_CONNECTIVITY 5
+
+/*
+ * MCU-specific values.
+ *
+ * You can use this section to override any of the below settings on a
+ * per-MCU basis. For example, if your MCU has different STM32_PCLK1
+ * or STM32_PCLK2 values, you can set them here and the values for
+ * STM32F103 microcontrollers set below won't take effect.
+ */
+
+#if defined(MCU_STM32F103RB)
+# define STM32_F1_LINE STM32_F1_LINE_PERFORMANCE
+# define STM32_NR_GPIO_PORTS 4
+# define STM32_SRAM_END ((void*)0x20005000)
+# define STM32_MEDIUM_DENSITY
+
+#elif defined(MCU_STM32F103ZE)
+# define STM32_F1_LINE STM32_F1_LINE_PERFORMANCE
+# define STM32_NR_GPIO_PORTS 7
+# define STM32_SRAM_END ((void*)0x20010000)
+# define STM32_HIGH_DENSITY
+
+#elif defined(MCU_STM32F103CB)
+# define STM32_F1_LINE STM32_F1_LINE_PERFORMANCE
+ /* This STM32_NR_GPIO_PORTS is not true, but only pins 0 and
+ * exist, and they're used for OSC (e.g. on LeafLabs' Maple Mini),
+ * so we'll live with this for now. */
+# define STM32_NR_GPIO_PORTS 3
+# define STM32_SRAM_END ((void*)0x20005000)
+# define STM32_MEDIUM_DENSITY
+
+#elif defined(MCU_STM32F103RE)
+# define STM32_F1_LINE STM32_F1_LINE_PERFORMANCE
+# define STM32_NR_GPIO_PORTS 4
+# define STM32_SRAM_END ((void*)0x20010000)
+# define STM32_HIGH_DENSITY
+
+#elif defined(MCU_STM32F100RB)
+# define STM32_F1_LINE STM32_F1_LINE_VALUE
+# define STM32_NR_GPIO_PORTS 4
+# define STM32_TIMER_MASK 0x380DE /* Timers: 1-4, 6, 7, 15-17. */
+# define STM32_SRAM_END ((void*)0x20002000)
+# define STM32_MEDIUM_DENSITY
+
+#elif defined(MCU_STM32F103C8)
+# define STM32_NR_GPIO_PORTS 4
+# define STM32_SRAM_END ((void*)0x20005000)
+# define NR_GPIO_PORTS STM32_NR_GPIO_PORTS
+# define STM32_F1_LINE STM32_F1_LINE_PERFORMANCE
+# define STM32_MEDIUM_DENSITY
+
+#else
+#warning "Unsupported or unspecified STM32F1 MCU."
+#endif
+
+/*
+ * Derived values.
+ */
+
+#if STM32_F1_LINE == STM32_F1_LINE_PERFORMANCE
+ /* All supported performance line MCUs have a USB peripheral */
+# define STM32_HAVE_USB 1
+
+# ifdef STM32_MEDIUM_DENSITY
+# define STM32_NR_INTERRUPTS 43
+# define STM32_TIMER_MASK 0x1E /* TIMER1--TIMER4 */
+# define STM32_HAVE_FSMC 0
+# define STM32_HAVE_DAC 0
+# elif defined(STM32_HIGH_DENSITY)
+# define STM32_NR_INTERRUPTS 60
+# define STM32_TIMER_MASK 0x1FE /* TIMER1--TIMER8 */
+# define STM32_HAVE_FSMC 1
+# define STM32_HAVE_DAC 1
+# elif defined(STM32_XL_DENSITY)
+# define STM32_NR_INTERRUPTS 60
+# define STM32_TIMER_MASK 0x7FFE /* TIMER1--TIMER14 */
+# define STM32_HAVE_FSMC 1
+# define STM32_HAVE_DAC 1
+# endif
+
+#elif STM32_F1_LINE == STM32_F1_LINE_VALUE
+ /* Value line MCUs don't have USB peripherals. */
+# define STM32_HAVE_USB 0
+
+# ifdef STM32_MEDIUM_DENSITY
+# define STM32_NR_INTERRUPTS 56
+# define STM32_HAVE_FSMC 0
+# define STM32_HAVE_DAC 1
+# elif defined(STM32_HIGH_DENSITY)
+ /* 61 interrupts here counts the possibility for a remapped
+ * DMA2 channel 5 IRQ occurring at NVIC index 60. */
+# define STM32_NR_INTERRUPTS 61
+# define STM32_HAVE_FSMC 1
+# define STM32_HAVE_DAC 1
+# endif
+
+#endif
+
+/*
+ * Clock configuration.
+ *
+ * You can patch these for your line, MCU, clock configuration,
+ * etc. here or by setting cflags when compiling libmaple.
+ */
+
+#if STM32_F1_LINE == STM32_F1_LINE_PERFORMANCE
+# ifndef STM32_PCLK1
+# define STM32_PCLK1 36000000U
+# endif
+# ifndef STM32_PCLK2
+# define STM32_PCLK2 72000000U
+# endif
+# ifndef STM32_DELAY_US_MULT
+# define STM32_DELAY_US_MULT 12 /* FIXME: value is incorrect. */
+# endif
+#elif STM32_F1_LINE == STM32_F1_LINE_VALUE /* TODO */
+# ifndef STM32_PCLK1
+# define STM32_PCLK1 12000000U
+# endif
+# ifndef STM32_PCLK2
+# define STM32_PCLK2 24000000U
+# endif
+# ifndef STM32_DELAY_US_MULT
+# define STM32_DELAY_US_MULT 8 /* FIXME: value is incorrect. */
+# endif
+#elif STM32_F1_LINE == STM32_F1_LINE_ACCESS /* TODO */
+#elif STM32_F1_LINE == STM32_F1_LINE_USB_ACCESS /* TODO */
+#elif STM32_F1_LINE == STM32_F1_LINE_CONNECTIVITY /* TODO */
+#endif
+
+/*
+ * Sanity checks.
+ *
+ * Make sure we have the F1-specific defines we need.
+ * <libmaple/stm32.h> will check that we've defined everything it needs.
+ */
+
+#if !defined(STM32_F1_LINE)
+#error "Bad STM32F1 configuration. Check STM32F1 <series/stm32.h> header."
+#endif
+
+/*
+ * Doxygen
+ */
+
+#ifdef __DOXYGEN__
+
+/**
+ * @brief STM32 line value for the STM32F1 MCU being targeted.
+ *
+ * At time of writing, allowed values are: STM32_F1_LINE_PERFORMANCE,
+ * STM32_F1_LINE_VALUE. This set of values may expand as libmaple adds
+ * support for more STM32F1 lines.
+ */
+#define STM32_F1_LINE
+
+#endif /* __DOXYGEN__ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/libmaple/stm32f1/include/series/timer.h b/libmaple/stm32f1/include/series/timer.h
new file mode 100644
index 0000000..cfeb770
--- /dev/null
+++ b/libmaple/stm32f1/include/series/timer.h
@@ -0,0 +1,128 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/include/series/timer.h
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief STM32F1 timer support.
+ */
+
+#ifndef _LIBMAPLE_STM32F1_TIMER_H_
+#define _LIBMAPLE_STM32F1_TIMER_H_
+
+#include <libmaple/libmaple_types.h>
+
+/*
+ * Register maps and base pointers
+ */
+
+/** STM32F1 general purpose timer register map type */
+typedef struct timer_gen_reg_map {
+ __io uint32 CR1; /**< Control register 1 */
+ __io uint32 CR2; /**< Control register 2 */
+ __io uint32 SMCR; /**< Slave mode control register */
+ __io uint32 DIER; /**< DMA/Interrupt enable register */
+ __io uint32 SR; /**< Status register */
+ __io uint32 EGR; /**< Event generation register */
+ __io uint32 CCMR1; /**< Capture/compare mode register 1 */
+ __io uint32 CCMR2; /**< Capture/compare mode register 2 */
+ __io uint32 CCER; /**< Capture/compare enable register */
+ __io uint32 CNT; /**< Counter */
+ __io uint32 PSC; /**< Prescaler */
+ __io uint32 ARR; /**< Auto-reload register */
+ const uint32 RESERVED1; /**< Reserved */
+ __io uint32 CCR1; /**< Capture/compare register 1 */
+ __io uint32 CCR2; /**< Capture/compare register 2 */
+ __io uint32 CCR3; /**< Capture/compare register 3 */
+ __io uint32 CCR4; /**< Capture/compare register 4 */
+ const uint32 RESERVED2; /**< Reserved */
+ __io uint32 DCR; /**< DMA control register */
+ __io uint32 DMAR; /**< DMA address for full transfer */
+} timer_gen_reg_map;
+
+struct timer_adv_reg_map;
+struct timer_bas_reg_map;
+
+/** Timer 1 register map base pointer */
+#define TIMER1_BASE ((struct timer_adv_reg_map*)0x40012C00)
+/** Timer 2 register map base pointer */
+#define TIMER2_BASE ((struct timer_gen_reg_map*)0x40000000)
+/** Timer 3 register map base pointer */
+#define TIMER3_BASE ((struct timer_gen_reg_map*)0x40000400)
+/** Timer 4 register map base pointer */
+#define TIMER4_BASE ((struct timer_gen_reg_map*)0x40000800)
+/** Timer 5 register map base pointer */
+#define TIMER5_BASE ((struct timer_gen_reg_map*)0x40000C00)
+/** Timer 6 register map base pointer */
+#define TIMER6_BASE ((struct timer_bas_reg_map*)0x40001000)
+/** Timer 7 register map base pointer */
+#define TIMER7_BASE ((struct timer_bas_reg_map*)0x40001400)
+/** Timer 8 register map base pointer */
+#define TIMER8_BASE ((struct timer_adv_reg_map*)0x40013400)
+/** Timer 9 register map base pointer */
+#define TIMER9_BASE ((struct timer_gen_reg_map*)0x40014C00)
+/** Timer 10 register map base pointer */
+#define TIMER10_BASE ((struct timer_gen_reg_map*)0x40015000)
+/** Timer 11 register map base pointer */
+#define TIMER11_BASE ((struct timer_gen_reg_map*)0x40015400)
+/** Timer 12 register map base pointer */
+#define TIMER12_BASE ((struct timer_gen_reg_map*)0x40001800)
+/** Timer 13 register map base pointer */
+#define TIMER13_BASE ((struct timer_gen_reg_map*)0x40001C00)
+/** Timer 14 register map base pointer */
+#define TIMER14_BASE ((struct timer_gen_reg_map*)0x40002000)
+
+/*
+ * Device pointers
+ *
+ * We only declare device pointers to timers which actually exist on
+ * the target MCU. This helps when porting programs to STM32F1 (or
+ * within F1 to a lower density MCU), as attempts to use nonexistent
+ * timers cause build errors instead of undefined behavior.
+ */
+
+struct timer_dev;
+
+extern struct timer_dev *TIMER1;
+extern struct timer_dev *TIMER2;
+extern struct timer_dev *TIMER3;
+extern struct timer_dev *TIMER4;
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+extern struct timer_dev *TIMER5;
+extern struct timer_dev *TIMER6;
+extern struct timer_dev *TIMER7;
+extern struct timer_dev *TIMER8;
+#endif
+#ifdef STM32_XL_DENSITY
+extern struct timer_dev *TIMER9;
+extern struct timer_dev *TIMER10;
+extern struct timer_dev *TIMER11;
+extern struct timer_dev *TIMER12;
+extern struct timer_dev *TIMER13;
+extern struct timer_dev *TIMER14;
+#endif
+
+#endif
diff --git a/libmaple/stm32f1/include/series/usart.h b/libmaple/stm32f1/include/series/usart.h
new file mode 100644
index 0000000..d12a3e2
--- /dev/null
+++ b/libmaple/stm32f1/include/series/usart.h
@@ -0,0 +1,76 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/include/series/usart.h
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief STM32F1 USART support.
+ */
+
+#ifndef _LIBMAPLE_STM32F1_USART_H_
+#define _LIBMAPLE_STM32F1_USART_H_
+
+#ifdef __cplusplus
+extern "C"{
+#endif
+
+/*
+ * Register map base pointers
+ */
+
+struct usart_reg_map;
+
+/** USART1 register map base pointer */
+#define USART1_BASE ((struct usart_reg_map*)0x40013800)
+/** USART2 register map base pointer */
+#define USART2_BASE ((struct usart_reg_map*)0x40004400)
+/** USART3 register map base pointer */
+#define USART3_BASE ((struct usart_reg_map*)0x40004800)
+#ifdef STM32_HIGH_DENSITY
+/** UART4 register map base pointer */
+#define UART4_BASE ((struct usart_reg_map*)0x40004C00)
+/** UART5 register map base pointer */
+#define UART5_BASE ((struct usart_reg_map*)0x40005000)
+#endif
+
+/*
+ * Devices
+ */
+
+struct usart_dev;
+extern struct usart_dev *USART1;
+extern struct usart_dev *USART2;
+extern struct usart_dev *USART3;
+#ifdef STM32_HIGH_DENSITY
+extern struct usart_dev *UART4;
+extern struct usart_dev *UART5;
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/libmaple/stm32f1/performance/isrs.S b/libmaple/stm32f1/performance/isrs.S
new file mode 100644
index 0000000..c638078
--- /dev/null
+++ b/libmaple/stm32f1/performance/isrs.S
@@ -0,0 +1,263 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2011 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.
+ *****************************************************************************/
+
+/* STM32F1 performance line ISR weak declarations */
+
+#include <libmaple/stm32.h>
+
+ .thumb
+
+/* Default handler for all non-overridden interrupts and exceptions */
+ .globl __default_handler
+ .type __default_handler, %function
+
+__default_handler:
+ b .
+
+ .weak __exc_nmi
+ .globl __exc_nmi
+ .set __exc_nmi, __default_handler
+ .weak __exc_hardfault
+ .globl __exc_hardfault
+ .set __exc_hardfault, __default_handler
+ .weak __exc_memmanage
+ .globl __exc_memmanage
+ .set __exc_memmanage, __default_handler
+ .weak __exc_busfault
+ .globl __exc_busfault
+ .set __exc_busfault, __default_handler
+ .weak __exc_usagefault
+ .globl __exc_usagefault
+ .set __exc_usagefault, __default_handler
+ .weak __stm32reservedexception7
+ .globl __stm32reservedexception7
+ .set __stm32reservedexception7, __default_handler
+ .weak __stm32reservedexception8
+ .globl __stm32reservedexception8
+ .set __stm32reservedexception8, __default_handler
+ .weak __stm32reservedexception9
+ .globl __stm32reservedexception9
+ .set __stm32reservedexception9, __default_handler
+ .weak __stm32reservedexception10
+ .globl __stm32reservedexception10
+ .set __stm32reservedexception10, __default_handler
+ .weak __exc_svc
+ .globl __exc_svc
+ .set __exc_svc, __default_handler
+ .weak __exc_debug_monitor
+ .globl __exc_debug_monitor
+ .set __exc_debug_monitor, __default_handler
+ .weak __stm32reservedexception13
+ .globl __stm32reservedexception13
+ .set __stm32reservedexception13, __default_handler
+ .weak __exc_pendsv
+ .globl __exc_pendsv
+ .set __exc_pendsv, __default_handler
+ .weak __exc_systick
+ .globl __exc_systick
+ .set __exc_systick, __default_handler
+ .weak __irq_wwdg
+ .globl __irq_wwdg
+ .set __irq_wwdg, __default_handler
+ .weak __irq_pvd
+ .globl __irq_pvd
+ .set __irq_pvd, __default_handler
+ .weak __irq_tamper
+ .globl __irq_tamper
+ .set __irq_tamper, __default_handler
+ .weak __irq_rtc
+ .globl __irq_rtc
+ .set __irq_rtc, __default_handler
+ .weak __irq_flash
+ .globl __irq_flash
+ .set __irq_flash, __default_handler
+ .weak __irq_rcc
+ .globl __irq_rcc
+ .set __irq_rcc, __default_handler
+ .weak __irq_exti0
+ .globl __irq_exti0
+ .set __irq_exti0, __default_handler
+ .weak __irq_exti1
+ .globl __irq_exti1
+ .set __irq_exti1, __default_handler
+ .weak __irq_exti2
+ .globl __irq_exti2
+ .set __irq_exti2, __default_handler
+ .weak __irq_exti3
+ .globl __irq_exti3
+ .set __irq_exti3, __default_handler
+ .weak __irq_exti4
+ .globl __irq_exti4
+ .set __irq_exti4, __default_handler
+ .weak __irq_dma1_channel1
+ .globl __irq_dma1_channel1
+ .set __irq_dma1_channel1, __default_handler
+ .weak __irq_dma1_channel2
+ .globl __irq_dma1_channel2
+ .set __irq_dma1_channel2, __default_handler
+ .weak __irq_dma1_channel3
+ .globl __irq_dma1_channel3
+ .set __irq_dma1_channel3, __default_handler
+ .weak __irq_dma1_channel4
+ .globl __irq_dma1_channel4
+ .set __irq_dma1_channel4, __default_handler
+ .weak __irq_dma1_channel5
+ .globl __irq_dma1_channel5
+ .set __irq_dma1_channel5, __default_handler
+ .weak __irq_dma1_channel6
+ .globl __irq_dma1_channel6
+ .set __irq_dma1_channel6, __default_handler
+ .weak __irq_dma1_channel7
+ .globl __irq_dma1_channel7
+ .set __irq_dma1_channel7, __default_handler
+ .weak __irq_adc
+ .globl __irq_adc
+ .set __irq_adc, __default_handler
+ .weak __irq_usb_hp_can_tx
+ .globl __irq_usb_hp_can_tx
+ .set __irq_usb_hp_can_tx, __default_handler
+ .weak __irq_usb_lp_can_rx0
+ .globl __irq_usb_lp_can_rx0
+ .set __irq_usb_lp_can_rx0, __default_handler
+ .weak __irq_can_rx1
+ .globl __irq_can_rx1
+ .set __irq_can_rx1, __default_handler
+ .weak __irq_can_sce
+ .globl __irq_can_sce
+ .set __irq_can_sce, __default_handler
+ .weak __irq_exti9_5
+ .globl __irq_exti9_5
+ .set __irq_exti9_5, __default_handler
+ .weak __irq_tim1_brk
+ .globl __irq_tim1_brk
+ .set __irq_tim1_brk, __default_handler
+ .weak __irq_tim1_up
+ .globl __irq_tim1_up
+ .set __irq_tim1_up, __default_handler
+ .weak __irq_tim1_trg_com
+ .globl __irq_tim1_trg_com
+ .set __irq_tim1_trg_com, __default_handler
+ .weak __irq_tim1_cc
+ .globl __irq_tim1_cc
+ .set __irq_tim1_cc, __default_handler
+ .weak __irq_tim2
+ .globl __irq_tim2
+ .set __irq_tim2, __default_handler
+ .weak __irq_tim3
+ .globl __irq_tim3
+ .set __irq_tim3, __default_handler
+ .weak __irq_tim4
+ .globl __irq_tim4
+ .set __irq_tim4, __default_handler
+ .weak __irq_i2c1_ev
+ .globl __irq_i2c1_ev
+ .set __irq_i2c1_ev, __default_handler
+ .weak __irq_i2c1_er
+ .globl __irq_i2c1_er
+ .set __irq_i2c1_er, __default_handler
+ .weak __irq_i2c2_ev
+ .globl __irq_i2c2_ev
+ .set __irq_i2c2_ev, __default_handler
+ .weak __irq_i2c2_er
+ .globl __irq_i2c2_er
+ .set __irq_i2c2_er, __default_handler
+ .weak __irq_spi1
+ .globl __irq_spi1
+ .set __irq_spi1, __default_handler
+ .weak __irq_spi2
+ .globl __irq_spi2
+ .set __irq_spi2, __default_handler
+ .weak __irq_usart1
+ .globl __irq_usart1
+ .set __irq_usart1, __default_handler
+ .weak __irq_usart2
+ .globl __irq_usart2
+ .set __irq_usart2, __default_handler
+ .weak __irq_usart3
+ .globl __irq_usart3
+ .set __irq_usart3, __default_handler
+ .weak __irq_exti15_10
+ .globl __irq_exti15_10
+ .set __irq_exti15_10, __default_handler
+ .weak __irq_rtcalarm
+ .globl __irq_rtcalarm
+ .set __irq_rtcalarm, __default_handler
+ .weak __irq_usbwakeup
+ .globl __irq_usbwakeup
+ .set __irq_usbwakeup, __default_handler
+#if defined (STM32_HIGH_DENSITY)
+ .weak __irq_tim8_brk
+ .globl __irq_tim8_brk
+ .set __irq_tim8_brk, __default_handler
+ .weak __irq_tim8_up
+ .globl __irq_tim8_up
+ .set __irq_tim8_up, __default_handler
+ .weak __irq_tim8_trg_com
+ .globl __irq_tim8_trg_com
+ .set __irq_tim8_trg_com, __default_handler
+ .weak __irq_tim8_cc
+ .globl __irq_tim8_cc
+ .set __irq_tim8_cc, __default_handler
+ .weak __irq_adc3
+ .globl __irq_adc3
+ .set __irq_adc3, __default_handler
+ .weak __irq_fsmc
+ .globl __irq_fsmc
+ .set __irq_fsmc, __default_handler
+ .weak __irq_sdio
+ .globl __irq_sdio
+ .set __irq_sdio, __default_handler
+ .weak __irq_tim5
+ .globl __irq_tim5
+ .set __irq_tim5, __default_handler
+ .weak __irq_spi3
+ .globl __irq_spi3
+ .set __irq_spi3, __default_handler
+ .weak __irq_uart4
+ .globl __irq_uart4
+ .set __irq_uart4, __default_handler
+ .weak __irq_uart5
+ .globl __irq_uart5
+ .set __irq_uart5, __default_handler
+ .weak __irq_tim6
+ .globl __irq_tim6
+ .set __irq_tim6, __default_handler
+ .weak __irq_tim7
+ .globl __irq_tim7
+ .set __irq_tim7, __default_handler
+ .weak __irq_dma2_channel1
+ .globl __irq_dma2_channel1
+ .set __irq_dma2_channel1, __default_handler
+ .weak __irq_dma2_channel2
+ .globl __irq_dma2_channel2
+ .set __irq_dma2_channel2, __default_handler
+ .weak __irq_dma2_channel3
+ .globl __irq_dma2_channel3
+ .set __irq_dma2_channel3, __default_handler
+ .weak __irq_dma2_channel4_5
+ .globl __irq_dma2_channel4_5
+ .set __irq_dma2_channel4_5, __default_handler
+#endif /* STM32_HIGH_DENSITY */
diff --git a/libmaple/stm32f1/performance/vector_table.S b/libmaple/stm32f1/performance/vector_table.S
new file mode 100644
index 0000000..8be3fa6
--- /dev/null
+++ b/libmaple/stm32f1/performance/vector_table.S
@@ -0,0 +1,118 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2011 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.
+ *****************************************************************************/
+
+/* STM32F1 performance line vector table */
+
+#include <libmaple/stm32.h>
+
+ .section ".stm32.interrupt_vector"
+
+ .globl __stm32_vector_table
+ .type __stm32_vector_table, %object
+
+__stm32_vector_table:
+/* CM3 core interrupts */
+ .long __msp_init
+ .long __exc_reset
+ .long __exc_nmi
+ .long __exc_hardfault
+ .long __exc_memmanage
+ .long __exc_busfault
+ .long __exc_usagefault
+ .long __stm32reservedexception7
+ .long __stm32reservedexception8
+ .long __stm32reservedexception9
+ .long __stm32reservedexception10
+ .long __exc_svc
+ .long __exc_debug_monitor
+ .long __stm32reservedexception13
+ .long __exc_pendsv
+ .long __exc_systick
+/* Peripheral interrupts */
+ .long __irq_wwdg
+ .long __irq_pvd
+ .long __irq_tamper
+ .long __irq_rtc
+ .long __irq_flash
+ .long __irq_rcc
+ .long __irq_exti0
+ .long __irq_exti1
+ .long __irq_exti2
+ .long __irq_exti3
+ .long __irq_exti4
+ .long __irq_dma1_channel1
+ .long __irq_dma1_channel2
+ .long __irq_dma1_channel3
+ .long __irq_dma1_channel4
+ .long __irq_dma1_channel5
+ .long __irq_dma1_channel6
+ .long __irq_dma1_channel7
+ .long __irq_adc
+ .long __irq_usb_hp_can_tx
+ .long __irq_usb_lp_can_rx0
+ .long __irq_can_rx1
+ .long __irq_can_sce
+ .long __irq_exti9_5
+ .long __irq_tim1_brk
+ .long __irq_tim1_up
+ .long __irq_tim1_trg_com
+ .long __irq_tim1_cc
+ .long __irq_tim2
+ .long __irq_tim3
+ .long __irq_tim4
+ .long __irq_i2c1_ev
+ .long __irq_i2c1_er
+ .long __irq_i2c2_ev
+ .long __irq_i2c2_er
+ .long __irq_spi1
+ .long __irq_spi2
+ .long __irq_usart1
+ .long __irq_usart2
+ .long __irq_usart3
+ .long __irq_exti15_10
+ .long __irq_rtcalarm
+ .long __irq_usbwakeup
+#if defined (STM32_HIGH_DENSITY)
+ .long __irq_tim8_brk
+ .long __irq_tim8_up
+ .long __irq_tim8_trg_com
+ .long __irq_tim8_cc
+ .long __irq_adc3
+ .long __irq_fsmc
+ .long __irq_sdio
+ .long __irq_tim5
+ .long __irq_spi3
+ .long __irq_uart4
+ .long __irq_uart5
+ .long __irq_tim6
+ .long __irq_tim7
+ .long __irq_dma2_channel1
+ .long __irq_dma2_channel2
+ .long __irq_dma2_channel3
+ .long __irq_dma2_channel4_5
+#endif /* STM32_HIGH_DENSITY */
+
+ .size __stm32_vector_table, . - __stm32_vector_table
diff --git a/libmaple/stm32f1/rcc.c b/libmaple/stm32f1/rcc.c
new file mode 100644
index 0000000..8d71a41
--- /dev/null
+++ b/libmaple/stm32f1/rcc.c
@@ -0,0 +1,164 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2011 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/rcc.c
+ * @brief STM32F1 RCC.
+ */
+
+#include <libmaple/rcc.h>
+#include <libmaple/libmaple.h>
+#include <libmaple/bitband.h>
+
+#include "rcc_private.h"
+
+#define APB1 RCC_APB1
+#define APB2 RCC_APB2
+#define AHB RCC_AHB
+
+/* Device descriptor table, maps rcc_clk_id onto bus and enable/reset
+ * register bit numbers. */
+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},
+ [RCC_USB] = { .clk_domain = APB1, .line_num = 23},
+#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
+};
+
+__deprecated
+void rcc_clk_init(rcc_sysclk_src sysclk_src,
+ rcc_pllsrc pll_src,
+ rcc_pll_multiplier pll_mul) {
+ /* 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, and wait for, HSE. */
+ rcc_turn_on_clk(RCC_CLK_HSE);
+ while (!rcc_is_clk_ready(RCC_CLK_HSE))
+ ;
+
+ /* Do the same for the main PLL. */
+ rcc_turn_on_clk(RCC_CLK_PLL);
+ while(!rcc_is_clk_ready(RCC_CLK_PLL))
+ ;
+
+ /* Finally, switch over to the PLL. */
+ rcc_switch_sysclk(RCC_CLKSRC_PLL);
+}
+
+/* pll_cfg->data must point to a valid struct stm32f1_rcc_pll_data. */
+void rcc_configure_pll(rcc_pll_cfg *pll_cfg) {
+ stm32f1_rcc_pll_data *data = pll_cfg->data;
+ rcc_pll_multiplier pll_mul = data->pll_mul;
+ uint32 cfgr;
+
+ /* Check that the PLL is disabled. */
+ ASSERT_FAULT(!rcc_is_clk_on(RCC_CLK_PLL));
+
+ cfgr = RCC_BASE->CFGR;
+ cfgr &= ~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLMUL);
+ cfgr |= pll_cfg->pllsrc | pll_mul;
+ RCC_BASE->CFGR = cfgr;
+}
+
+void rcc_clk_enable(rcc_clk_id id) {
+ static __io uint32* enable_regs[] = {
+ [APB1] = &RCC_BASE->APB1ENR,
+ [APB2] = &RCC_BASE->APB2ENR,
+ [AHB] = &RCC_BASE->AHBENR,
+ };
+ rcc_do_clk_enable(enable_regs, id);
+}
+
+void rcc_reset_dev(rcc_clk_id id) {
+ static __io uint32* reset_regs[] = {
+ [APB1] = &RCC_BASE->APB1RSTR,
+ [APB2] = &RCC_BASE->APB2RSTR,
+ };
+ rcc_do_reset_dev(reset_regs, id);
+}
+
+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,
+ };
+ rcc_do_set_prescaler(masks, prescaler, divider);
+}
diff --git a/libmaple/stm32f1/rules.mk b/libmaple/stm32f1/rules.mk
new file mode 100644
index 0000000..f1cc23e
--- /dev/null
+++ b/libmaple/stm32f1/rules.mk
@@ -0,0 +1,45 @@
+# Standard things
+sp := $(sp).x
+dirstack_$(sp) := $(d)
+d := $(dir)
+BUILDDIRS += $(BUILD_PATH)/$(d)
+
+# Local flags
+CFLAGS_$(d) = -I$(d) $(LIBMAPLE_PRIVATE_INCLUDES) $(LIBMAPLE_INCLUDES) -Wall -Werror
+ASFLAGS_$(d) = -I$(d) $(LIBMAPLE_PRIVATE_INCLUDES) $(LIBMAPLE_INCLUDES) -Wall -Werror
+
+# Extra BUILDDIRS
+BUILDDIRS += $(BUILD_PATH)/$(d)/$(MCU_F1_LINE)
+
+# Local rules and targets
+sSRCS_$(d) := $(MCU_F1_LINE)/isrs.S
+sSRCS_$(d) += $(MCU_F1_LINE)/vector_table.S
+
+cSRCS_$(d) := adc.c
+cSRCS_$(d) += bkp.c
+cSRCS_$(d) += dma.c
+cSRCS_$(d) += exti.c
+cSRCS_$(d) += fsmc.c
+cSRCS_$(d) += gpio.c
+cSRCS_$(d) += i2c.c
+cSRCS_$(d) += rcc.c
+cSRCS_$(d) += spi.c
+cSRCS_$(d) += timer.c
+cSRCS_$(d) += usart.c
+
+sFILES_$(d) := $(sSRCS_$(d):%=$(d)/%)
+cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%)
+
+OBJS_$(d) := $(sFILES_$(d):%.S=$(BUILD_PATH)/%.o) \
+ $(cFILES_$(d):%.c=$(BUILD_PATH)/%.o)
+DEPS_$(d) := $(OBJS_$(d):%.o=%.d)
+
+$(OBJS_$(d)): TGT_ASFLAGS := $(ASFLAGS_$(d))
+$(OBJS_$(d)): TGT_CFLAGS := $(CFLAGS_$(d))
+
+TGT_BIN += $(OBJS_$(d))
+
+# Standard things
+-include $(DEPS_$(d))
+d := $(dirstack_$(sp))
+sp := $(basename $(sp))
diff --git a/libmaple/stm32f1/spi.c b/libmaple/stm32f1/spi.c
new file mode 100644
index 0000000..1c78cc3
--- /dev/null
+++ b/libmaple/stm32f1/spi.c
@@ -0,0 +1,84 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
+ * 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 libmaple/stm32f1/spi.c
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief STM32F1 SPI/I2S.
+ */
+
+#include <libmaple/spi.h>
+#include <libmaple/gpio.h>
+#include "spi_private.h"
+
+/*
+ * Devices
+ */
+
+static spi_dev spi1 = SPI_DEV(1);
+static spi_dev spi2 = SPI_DEV(2);
+
+spi_dev *SPI1 = &spi1;
+spi_dev *SPI2 = &spi2;
+
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+static spi_dev spi3 = SPI_DEV(3);
+spi_dev *SPI3 = &spi3;
+#endif
+
+/*
+ * Routines
+ */
+
+void spi_config_gpios(spi_dev *ignored,
+ uint8 as_master,
+ gpio_dev *nss_dev,
+ uint8 nss_bit,
+ gpio_dev *comm_dev,
+ uint8 sck_bit,
+ uint8 miso_bit,
+ uint8 mosi_bit) {
+ if (as_master) {
+ gpio_set_mode(nss_dev, nss_bit, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(comm_dev, sck_bit, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(comm_dev, miso_bit, GPIO_INPUT_FLOATING);
+ gpio_set_mode(comm_dev, mosi_bit, GPIO_AF_OUTPUT_PP);
+ } else {
+ gpio_set_mode(nss_dev, nss_bit, GPIO_INPUT_FLOATING);
+ gpio_set_mode(comm_dev, sck_bit, GPIO_INPUT_FLOATING);
+ gpio_set_mode(comm_dev, miso_bit, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(comm_dev, mosi_bit, GPIO_INPUT_FLOATING);
+ }
+}
+
+void spi_foreach(void (*fn)(spi_dev*)) {
+ fn(SPI1);
+ fn(SPI2);
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+ fn(SPI3);
+#endif
+}
diff --git a/libmaple/stm32f1/timer.c b/libmaple/stm32f1/timer.c
new file mode 100644
index 0000000..8b9e976
--- /dev/null
+++ b/libmaple/stm32f1/timer.c
@@ -0,0 +1,124 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
+ *
+ * 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 libmaple/stm32f1/timer.c
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief STM32F1 timer.
+ */
+
+#include <libmaple/timer.h>
+#include <libmaple/stm32.h>
+#include "timer_private.h"
+
+/*
+ * IRQ handlers
+ *
+ * Defer to the timer_private dispatch API.
+ *
+ * FIXME: The names of these handlers are inaccurate since XL-density
+ * devices came out. Update these to match the STM32F2 names, maybe
+ * using some weak symbol magic to preserve backwards compatibility if
+ * possible. Once that's done, we can just move the IRQ handlers into
+ * the top-level libmaple/timer.c, and there will be no need for this
+ * file.
+ */
+
+void __irq_tim1_brk(void) {
+ dispatch_adv_brk(TIMER1);
+#if STM32_HAVE_TIMER(9)
+ dispatch_tim_9_12(TIMER9);
+#endif
+}
+
+void __irq_tim1_up(void) {
+ dispatch_adv_up(TIMER1);
+#if STM32_HAVE_TIMER(10)
+ dispatch_tim_10_11_13_14(TIMER10);
+#endif
+}
+
+void __irq_tim1_trg_com(void) {
+ dispatch_adv_trg_com(TIMER1);
+#if STM32_HAVE_TIMER(11)
+ dispatch_tim_10_11_13_14(TIMER11);
+#endif
+}
+
+void __irq_tim1_cc(void) {
+ dispatch_adv_cc(TIMER1);
+}
+
+void __irq_tim2(void) {
+ dispatch_general(TIMER2);
+}
+
+void __irq_tim3(void) {
+ dispatch_general(TIMER3);
+}
+
+void __irq_tim4(void) {
+ dispatch_general(TIMER4);
+}
+
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+void __irq_tim5(void) {
+ dispatch_general(TIMER5);
+}
+
+void __irq_tim6(void) {
+ dispatch_basic(TIMER6);
+}
+
+void __irq_tim7(void) {
+ dispatch_basic(TIMER7);
+}
+
+void __irq_tim8_brk(void) {
+ dispatch_adv_brk(TIMER8);
+#if STM32_HAVE_TIMER(12)
+ dispatch_tim_9_12(TIMER12);
+#endif
+}
+
+void __irq_tim8_up(void) {
+ dispatch_adv_up(TIMER8);
+#if STM32_HAVE_TIMER(13)
+ dispatch_tim_10_11_13_14(TIMER13);
+#endif
+}
+
+void __irq_tim8_trg_com(void) {
+ dispatch_adv_trg_com(TIMER8);
+#if STM32_HAVE_TIMER(14)
+ dispatch_tim_10_11_13_14(TIMER14);
+#endif
+}
+
+void __irq_tim8_cc(void) {
+ dispatch_adv_cc(TIMER8);
+}
+#endif /* defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) */
diff --git a/libmaple/stm32f1/usart.c b/libmaple/stm32f1/usart.c
new file mode 100644
index 0000000..b3b849f
--- /dev/null
+++ b/libmaple/stm32f1/usart.c
@@ -0,0 +1,170 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ * 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 libmaple/stm32f1/usart.c
+ * @author Marti Bolivar <mbolivar@leaflabs.com>,
+ * Perry Hung <perry@leaflabs.com>
+ * @brief STM32F1 USART.
+ */
+
+#include <libmaple/usart.h>
+#include <libmaple/gpio.h>
+#include "usart_private.h"
+
+/*
+ * Devices
+ */
+
+static ring_buffer usart1_rb;
+static usart_dev usart1 = {
+ .regs = USART1_BASE,
+ .rb = &usart1_rb,
+ .max_baud = 4500000UL,
+ .clk_id = RCC_USART1,
+ .irq_num = NVIC_USART1,
+};
+/** USART1 device */
+usart_dev *USART1 = &usart1;
+
+static ring_buffer usart2_rb;
+static usart_dev usart2 = {
+ .regs = USART2_BASE,
+ .rb = &usart2_rb,
+ .max_baud = 2250000UL,
+ .clk_id = RCC_USART2,
+ .irq_num = NVIC_USART2,
+};
+/** USART2 device */
+usart_dev *USART2 = &usart2;
+
+static ring_buffer usart3_rb;
+static usart_dev usart3 = {
+ .regs = USART3_BASE,
+ .rb = &usart3_rb,
+ .max_baud = 2250000UL,
+ .clk_id = RCC_USART3,
+ .irq_num = NVIC_USART3,
+};
+/** USART3 device */
+usart_dev *USART3 = &usart3;
+
+#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
+static ring_buffer uart4_rb;
+static usart_dev uart4 = {
+ .regs = UART4_BASE,
+ .rb = &uart4_rb,
+ .max_baud = 2250000UL,
+ .clk_id = RCC_UART4,
+ .irq_num = NVIC_UART4,
+};
+/** UART4 device */
+usart_dev *UART4 = &uart4;
+
+static ring_buffer uart5_rb;
+static usart_dev uart5 = {
+ .regs = UART5_BASE,
+ .rb = &uart5_rb,
+ .max_baud = 2250000UL,
+ .clk_id = RCC_UART5,
+ .irq_num = NVIC_UART5,
+};
+/** UART5 device */
+usart_dev *UART5 = &uart5;
+#endif
+
+/*
+ * Routines
+ */
+
+void usart_config_gpios_async(usart_dev *udev,
+ gpio_dev *rx_dev, uint8 rx,
+ gpio_dev *tx_dev, uint8 tx,
+ unsigned flags) {
+ gpio_set_mode(rx_dev, rx, GPIO_INPUT_FLOATING);
+ gpio_set_mode(tx_dev, tx, GPIO_AF_OUTPUT_PP);
+}
+
+void usart_set_baud_rate(usart_dev *dev, uint32 clock_speed, uint32 baud) {
+ uint32 integer_part;
+ uint32 fractional_part;
+ uint32 tmp;
+
+ /* Figure out the clock speed, if the user doesn't give one. */
+ if (clock_speed == 0) {
+ clock_speed = _usart_clock_freq(dev);
+ }
+ ASSERT(clock_speed);
+
+ /* Convert desired baud rate to baud rate register setting. */
+ integer_part = (25 * clock_speed) / (4 * baud);
+ tmp = (integer_part / 100) << 4;
+ fractional_part = integer_part - (100 * (tmp >> 4));
+ tmp |= (((fractional_part * 16) + 50) / 100) & ((uint8)0x0F);
+
+ dev->regs->BRR = (uint16)tmp;
+}
+
+/**
+ * @brief Call a function on each USART.
+ * @param fn Function to call.
+ */
+void usart_foreach(void (*fn)(usart_dev*)) {
+ fn(USART1);
+ fn(USART2);
+ fn(USART3);
+#ifdef STM32_HIGH_DENSITY
+ fn(UART4);
+ fn(UART5);
+#endif
+}
+
+/*
+ * Interrupt handlers.
+ */
+
+void __irq_usart1(void) {
+ usart_irq(&usart1_rb, USART1_BASE);
+}
+
+void __irq_usart2(void) {
+ usart_irq(&usart2_rb, USART2_BASE);
+}
+
+void __irq_usart3(void) {
+ usart_irq(&usart3_rb, USART3_BASE);
+}
+
+#ifdef STM32_HIGH_DENSITY
+void __irq_uart4(void) {
+ usart_irq(&uart4_rb, UART4_BASE);
+}
+
+void __irq_uart5(void) {
+ usart_irq(&uart5_rb, UART5_BASE);
+}
+#endif
diff --git a/libmaple/stm32f1/value/isrs.S b/libmaple/stm32f1/value/isrs.S
new file mode 100644
index 0000000..858016b
--- /dev/null
+++ b/libmaple/stm32f1/value/isrs.S
@@ -0,0 +1,270 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2011 Perry Hung.
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * 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.
+ *****************************************************************************/
+
+/* STM32F1 value line ISR weak declarations */
+
+ .thumb
+
+/* Default handler for all non-overridden interrupts and exceptions */
+ .globl __default_handler
+ .type __default_handler, %function
+
+__default_handler:
+ b .
+
+ .weak __msp_init
+ .globl __msp_init
+ .set __msp_init, __default_handler
+ .weak __exc_reset
+ .globl __exc_reset
+ .set __exc_reset, __default_handler
+ .weak __exc_nmi
+ .globl __exc_nmi
+ .set __exc_nmi, __default_handler
+ .weak __exc_hardfault
+ .globl __exc_hardfault
+ .set __exc_hardfault, __default_handler
+ .weak __exc_memmanage
+ .globl __exc_memmanage
+ .set __exc_memmanage, __default_handler
+ .weak __exc_busfault
+ .globl __exc_busfault
+ .set __exc_busfault, __default_handler
+ .weak __exc_usagefault
+ .globl __exc_usagefault
+ .set __exc_usagefault, __default_handler
+ .weak __stm32reservedexception7
+ .globl __stm32reservedexception7
+ .set __stm32reservedexception7, __default_handler
+ .weak __stm32reservedexception8
+ .globl __stm32reservedexception8
+ .set __stm32reservedexception8, __default_handler
+ .weak __stm32reservedexception9
+ .globl __stm32reservedexception9
+ .set __stm32reservedexception9, __default_handler
+ .weak __stm32reservedexception10
+ .globl __stm32reservedexception10
+ .set __stm32reservedexception10, __default_handler
+ .weak __exc_svc
+ .globl __exc_svc
+ .set __exc_svc, __default_handler
+ .weak __exc_debug_monitor
+ .globl __exc_debug_monitor
+ .set __exc_debug_monitor, __default_handler
+ .weak __stm32reservedexception13
+ .globl __stm32reservedexception13
+ .set __stm32reservedexception13, __default_handler
+ .weak __exc_pendsv
+ .globl __exc_pendsv
+ .set __exc_pendsv, __default_handler
+ .weak __exc_systick
+ .globl __exc_systick
+ .set __exc_systick, __default_handler
+
+ .weak __irq_wwdg
+ .globl __irq_wwdg
+ .set __irq_wwdg, __default_handler
+ .weak __irq_pvd
+ .globl __irq_pvd
+ .set __irq_pvd, __default_handler
+ .weak __irq_tamper
+ .globl __irq_tamper
+ .set __irq_tamper, __default_handler
+ .weak __irq_rtc
+ .globl __irq_rtc
+ .set __irq_rtc, __default_handler
+ .weak __irq_flash
+ .globl __irq_flash
+ .set __irq_flash, __default_handler
+ .weak __irq_rcc
+ .globl __irq_rcc
+ .set __irq_rcc, __default_handler
+ .weak __irq_exti0
+ .globl __irq_exti0
+ .set __irq_exti0, __default_handler
+ .weak __irq_exti1
+ .globl __irq_exti1
+ .set __irq_exti1, __default_handler
+ .weak __irq_exti2
+ .globl __irq_exti2
+ .set __irq_exti2, __default_handler
+ .weak __irq_exti3
+ .globl __irq_exti3
+ .set __irq_exti3, __default_handler
+ .weak __irq_exti4
+ .globl __irq_exti4
+ .set __irq_exti4, __default_handler
+ .weak __irq_dma1_channel1
+ .globl __irq_dma1_channel1
+ .set __irq_dma1_channel1, __default_handler
+ .weak __irq_dma1_channel2
+ .globl __irq_dma1_channel2
+ .set __irq_dma1_channel2, __default_handler
+ .weak __irq_dma1_channel3
+ .globl __irq_dma1_channel3
+ .set __irq_dma1_channel3, __default_handler
+ .weak __irq_dma1_channel4
+ .globl __irq_dma1_channel4
+ .set __irq_dma1_channel4, __default_handler
+ .weak __irq_dma1_channel5
+ .globl __irq_dma1_channel5
+ .set __irq_dma1_channel5, __default_handler
+ .weak __irq_dma1_channel6
+ .globl __irq_dma1_channel6
+ .set __irq_dma1_channel6, __default_handler
+ .weak __irq_dma1_channel7
+ .globl __irq_dma1_channel7
+ .set __irq_dma1_channel7, __default_handler
+ .weak __irq_adc1
+ .globl __irq_adc1
+ .set __irq_adc1, __default_handler
+ .weak __stm32reservedexception14
+ .globl __stm32reservedexception14
+ .set __stm32reservedexception14, __default_handler
+ .weak __stm32reservedexception15
+ .globl __stm32reservedexception15
+ .set __stm32reservedexception15, __default_handler
+ .weak __stm32reservedexception16
+ .globl __stm32reservedexception16
+ .set __stm32reservedexception16, __default_handler
+ .weak __stm32reservedexception17
+ .globl __stm32reservedexception17
+ .set __stm32reservedexception17, __default_handler
+ .weak __irq_exti9_5
+ .globl __irq_exti9_5
+ .set __irq_exti9_5, __default_handler
+ .weak __irq_tim1_brk
+ .globl __irq_tim1_brk
+ .set __irq_tim1_brk, __default_handler
+ .weak __irq_tim1_up
+ .globl __irq_tim1_up
+ .set __irq_tim1_up, __default_handler
+ .weak __irq_tim1_trg_com
+ .globl __irq_tim1_trg_com
+ .set __irq_tim1_trg_com, __default_handler
+ .weak __irq_tim1_cc
+ .globl __irq_tim1_cc
+ .set __irq_tim1_cc, __default_handler
+ .weak __irq_tim2
+ .globl __irq_tim2
+ .set __irq_tim2, __default_handler
+ .weak __irq_tim3
+ .globl __irq_tim3
+ .set __irq_tim3, __default_handler
+ .weak __irq_tim4
+ .globl __irq_tim4
+ .set __irq_tim4, __default_handler
+ .weak __irq_i2c1_ev
+ .globl __irq_i2c1_ev
+ .set __irq_i2c1_ev, __default_handler
+ .weak __irq_i2c1_er
+ .globl __irq_i2c1_er
+ .set __irq_i2c1_er, __default_handler
+ .weak __irq_i2c2_ev
+ .globl __irq_i2c2_ev
+ .set __irq_i2c2_ev, __default_handler
+ .weak __irq_i2c2_er
+ .globl __irq_i2c2_er
+ .set __irq_i2c2_er, __default_handler
+ .weak __irq_spi1
+ .globl __irq_spi1
+ .set __irq_spi1, __default_handler
+ .weak __irq_spi2
+ .globl __irq_spi2
+ .set __irq_spi2, __default_handler
+ .weak __irq_usart1
+ .globl __irq_usart1
+ .set __irq_usart1, __default_handler
+ .weak __irq_usart2
+ .globl __irq_usart2
+ .set __irq_usart2, __default_handler
+ .weak __irq_usart3
+ .globl __irq_usart3
+ .set __irq_usart3, __default_handler
+ .weak __irq_exti15_10
+ .globl __irq_exti15_10
+ .set __irq_exti15_10, __default_handler
+ .weak __irq_rtcalarm
+ .globl __irq_rtcalarm
+ .set __irq_rtcalarm, __default_handler
+ .weak __irq_cec
+ .globl __irq_cec
+ .set __irq_cec, __default_handler
+ .weak __irq_tim12
+ .globl __irq_tim12
+ .set __irq_tim12, __default_handler
+ .weak __irq_tim13
+ .globl __irq_tim13
+ .set __irq_tim13, __default_handler
+ .weak __irq_tim14
+ .globl __irq_tim14
+ .set __irq_tim14, __default_handler
+ .weak __stm32reservedexception18
+ .globl __stm32reservedexception18
+ .set __stm32reservedexception18, __default_handler
+ .weak __stm32reservedexception19
+ .globl __stm32reservedexception19
+ .set __stm32reservedexception19, __default_handler
+ .weak __irq_fsmc
+ .globl __irq_fsmc
+ .set __irq_fsmc, __default_handler
+ .weak __stm32reservedexception20
+ .globl __stm32reservedexception20
+ .set __stm32reservedexception20, __default_handler
+ .weak __irq_tim5
+ .globl __irq_tim5
+ .set __irq_tim5, __default_handler
+ .weak __irq_spi3
+ .globl __irq_spi3
+ .set __irq_spi3, __default_handler
+ .weak __irq_uart4
+ .globl __irq_uart4
+ .set __irq_uart4, __default_handler
+ .weak __irq_uart5
+ .globl __irq_uart5
+ .set __irq_uart5, __default_handler
+ .weak __irq_tim6
+ .globl __irq_tim6
+ .set __irq_tim6, __default_handler
+ .weak __irq_tim7
+ .globl __irq_tim7
+ .set __irq_tim7, __default_handler
+ .weak __irq_dma2_channel1
+ .globl __irq_dma2_channel1
+ .set __irq_dma2_channel1, __default_handler
+ .weak __irq_dma2_channel2
+ .globl __irq_dma2_channel2
+ .set __irq_dma2_channel2, __default_handler
+ .weak __irq_dma2_channel3
+ .globl __irq_dma2_channel3
+ .set __irq_dma2_channel3, __default_handler
+ .weak __irq_dma2_channel4_5
+ .globl __irq_dma2_channel4_5
+ .set __irq_dma2_channel4_5, __default_handler
+ .weak __irq_dma2_channel5 /* on remap only */
+ .globl __irq_dma2_channel5
+ .set __irq_dma2_channel5, __default_handler
diff --git a/libmaple/stm32f1/value/vector_table.S b/libmaple/stm32f1/value/vector_table.S
new file mode 100644
index 0000000..76a2a6e
--- /dev/null
+++ b/libmaple/stm32f1/value/vector_table.S
@@ -0,0 +1,116 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2011 Perry Hung.
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * 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.
+ *****************************************************************************/
+
+/* STM32F1 value line vector table */
+
+ .section ".stm32.interrupt_vector"
+
+ .globl __stm32_vector_table
+ .type __stm32_vector_table, %object
+
+__stm32_vector_table:
+/* CM3 core interrupts */
+ .long __msp_init
+ .long __exc_reset
+ .long __exc_nmi
+ .long __exc_hardfault
+ .long __exc_memmanage
+ .long __exc_busfault
+ .long __exc_usagefault
+ .long __stm32reservedexception7
+ .long __stm32reservedexception8
+ .long __stm32reservedexception9
+ .long __stm32reservedexception10
+ .long __exc_svc
+ .long __exc_debug_monitor
+ .long __stm32reservedexception13
+ .long __exc_pendsv
+ .long __exc_systick
+/* Peripheral interrupts */
+ .long __irq_wwdg
+ .long __irq_pvd
+ .long __irq_tamper
+ .long __irq_rtc
+ .long __irq_flash
+ .long __irq_rcc
+ .long __irq_exti0
+ .long __irq_exti1
+ .long __irq_exti2
+ .long __irq_exti3
+ .long __irq_exti4
+ .long __irq_dma1_channel1
+ .long __irq_dma1_channel2
+ .long __irq_dma1_channel3
+ .long __irq_dma1_channel4
+ .long __irq_dma1_channel5
+ .long __irq_dma1_channel6
+ .long __irq_dma1_channel7
+ .long __irq_adc1
+ .long __stm32reservedexception14
+ .long __stm32reservedexception15
+ .long __stm32reservedexception16
+ .long __stm32reservedexception17
+ .long __irq_exti9_5
+ .long __irq_tim1_brk
+ .long __irq_tim1_up
+ .long __irq_tim1_trg_com
+ .long __irq_tim1_cc
+ .long __irq_tim2
+ .long __irq_tim3
+ .long __irq_tim4
+ .long __irq_i2c1_ev
+ .long __irq_i2c1_er
+ .long __irq_i2c2_ev
+ .long __irq_i2c2_er
+ .long __irq_spi1
+ .long __irq_spi2
+ .long __irq_usart1
+ .long __irq_usart2
+ .long __irq_usart3
+ .long __irq_exti15_10
+ .long __irq_rtcalarm
+ .long __irq_cec
+ .long __irq_tim12
+ .long __irq_tim13
+ .long __irq_tim14
+ .long __stm32reservedexception18
+ .long __stm32reservedexception19
+ .long __irq_fsmc
+ .long __stm32reservedexception20
+ .long __irq_tim5
+ .long __irq_spi3
+ .long __irq_uart4
+ .long __irq_uart5
+ .long __irq_tim6
+ .long __irq_tim7
+ .long __irq_dma2_channel1
+ .long __irq_dma2_channel2
+ .long __irq_dma2_channel3
+ .long __irq_dma2_channel4_5
+ .long __irq_dma2_channel5 /* on remap only */
+
+ .size __stm32_vector_table, . - __stm32_vector_table