aboutsummaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
authorMarti Bolivar <mbolivar@leaflabs.com>2011-03-07 13:11:54 -0500
committerMarti Bolivar <mbolivar@leaflabs.com>2011-03-11 16:24:44 -0500
commitc8da1c3b7b6eb450138a00af9bbbee607f596837 (patch)
tree207777355d41dc8947d94665ef9a8bae8982805a
parent5b07707cdaa6268e1a984727bb907a7b10e8ada7 (diff)
downloadlibrambutan-c8da1c3b7b6eb450138a00af9bbbee607f596837.tar.gz
librambutan-c8da1c3b7b6eb450138a00af9bbbee607f596837.zip
[WIP] GPIO refactor: seems ok, ready for review
-rw-r--r--Makefile8
-rw-r--r--docs/Doxyfile6
-rw-r--r--examples/test-session.cpp28
-rw-r--r--libmaple/adc.c4
-rw-r--r--libmaple/adc.h38
-rw-r--r--libmaple/bitband.h83
-rw-r--r--libmaple/bkp.c6
-rw-r--r--libmaple/bkp.h16
-rw-r--r--libmaple/dac.c6
-rw-r--r--libmaple/dac.h10
-rw-r--r--libmaple/exti.c244
-rw-r--r--libmaple/exti.h158
-rw-r--r--libmaple/fsmc.c89
-rw-r--r--libmaple/fsmc.h5
-rw-r--r--libmaple/gpio.c165
-rw-r--r--libmaple/gpio.h391
-rw-r--r--libmaple/libmaple.h2
-rw-r--r--libmaple/libmaple_types.h1
-rw-r--r--libmaple/pwr.h9
-rw-r--r--libmaple/rcc.h3
-rw-r--r--libmaple/ring_buffer.h17
-rw-r--r--libmaple/spi.c18
-rw-r--r--libmaple/usb/usb.c33
-rw-r--r--libmaple/usb/usb_callbacks.c2
-rw-r--r--libmaple/usb/usb_config.h7
-rw-r--r--libmaple/usb/usb_hardware.c41
-rw-r--r--libmaple/usb/usb_hardware.h36
-rw-r--r--libmaple/util.c6
-rw-r--r--libmaple/util.h35
-rw-r--r--notes/coding_standard.txt85
-rw-r--r--notes/exti.txt67
-rw-r--r--wirish/HardwareTimer.cpp11
-rw-r--r--wirish/boards.cpp387
-rw-r--r--wirish/boards.h401
-rw-r--r--wirish/comm/HardwareSerial.cpp14
-rw-r--r--wirish/comm/HardwareSerial.h4
-rw-r--r--wirish/ext_interrupts.cpp (renamed from wirish/ext_interrupts.c)67
-rw-r--r--wirish/ext_interrupts.h11
-rw-r--r--wirish/io.h11
-rw-r--r--wirish/pwm.cpp (renamed from wirish/pwm.c)0
-rw-r--r--wirish/pwm.h13
-rw-r--r--wirish/rules.mk32
-rw-r--r--wirish/time.cpp (renamed from wirish/time.c)0
-rw-r--r--wirish/time.h9
-rw-r--r--wirish/wirish.cpp (renamed from wirish/wirish.c)5
-rw-r--r--wirish/wirish.h16
-rw-r--r--wirish/wirish_analog.cpp (renamed from wirish/wirish_analog.c)0
-rw-r--r--wirish/wirish_digital.cpp (renamed from wirish/wirish_digital.c)29
-rw-r--r--wirish/wirish_math.h9
-rw-r--r--wirish/wirish_shift.cpp (renamed from wirish/wirish_shift.c)0
50 files changed, 1493 insertions, 1145 deletions
diff --git a/Makefile b/Makefile
index 01e1e72..3804421 100644
--- a/Makefile
+++ b/Makefile
@@ -13,21 +13,21 @@ PRODUCT_ID := 0003
ifeq ($(BOARD), maple)
MCU := STM32F103RB
PRODUCT_ID := 0003
- ERROR_LED_PORT := GPIOA_BASE
+ ERROR_LED_PORT := GPIOA
ERROR_LED_PIN := 5
DENSITY := STM32_MEDIUM_DENSITY
endif
ifeq ($(BOARD), maple_native)
MCU := STM32F103ZE
PRODUCT_ID := 0003
- ERROR_LED_PORT := GPIOC_BASE
+ ERROR_LED_PORT := GPIOC
ERROR_LED_PIN := 15
DENSITY := STM32_HIGH_DENSITY
endif
ifeq ($(BOARD), maple_mini)
MCU := STM32F103CB
PRODUCT_ID := 0003
- ERROR_LED_PORT := GPIOB_BASE
+ ERROR_LED_PORT := GPIOB
ERROR_LED_PIN := 1
DENSITY := STM32_MEDIUM_DENSITY
endif
@@ -45,7 +45,7 @@ SUPPORT_PATH := $(SRCROOT)/support
# Compilation flags.
# FIXME remove the ERROR_LED config
GLOBAL_CFLAGS := -Os -g3 -gdwarf-2 -mcpu=cortex-m3 -mthumb -march=armv7-m \
- -nostdlib \
+ -nostdlib \
-ffunction-sections -fdata-sections -Wl,--gc-sections \
-DBOARD_$(BOARD) -DMCU_$(MCU) \
-DERROR_LED_PORT=$(ERROR_LED_PORT) \
diff --git a/docs/Doxyfile b/docs/Doxyfile
index 3290843..9bf02fc 100644
--- a/docs/Doxyfile
+++ b/docs/Doxyfile
@@ -620,7 +620,9 @@ RECURSIVE = YES
# excluded from the INPUT source files. This way you can easily exclude a
# subdirectory from a directory tree whose root is specified with the INPUT tag.
-EXCLUDE =
+# FIXME The USB thing needs to get redone (ST code stripped out,
+# etc.). Until then, just ignore it.
+EXCLUDE = ../libmaple/usb/
# The EXCLUDE_SYMLINKS tag can be used select whether or not files or
# directories that are symbolic links (a Unix filesystem feature) are excluded
@@ -1369,7 +1371,7 @@ INCLUDE_FILE_PATTERNS =
# undefined via #undef or recursively expanded use the := operator
# instead of the = operator.
-PREDEFINED = ALWAYS_INLINE= \
+PREDEFINED = __attribute__()= \
__cplusplus
# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then
diff --git a/examples/test-session.cpp b/examples/test-session.cpp
index 72d64d6..ea631ca 100644
--- a/examples/test-session.cpp
+++ b/examples/test-session.cpp
@@ -351,22 +351,22 @@ void cmd_everything(void) { // TODO
}
void fast_gpio(int maple_pin) {
- GPIO_Port *port = PIN_MAP[maple_pin].port;
+ gpio_dev *dev = PIN_MAP[maple_pin].gpio_device;
uint32 pin = PIN_MAP[maple_pin].pin;
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
- gpio_write_bit(port, pin, 1); gpio_write_bit(port, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
+ gpio_write_bit(dev, pin, 1); gpio_write_bit(dev, pin, 0);
}
void cmd_serial1_serial3(void) {
diff --git a/libmaple/adc.c b/libmaple/adc.c
index a464746..9626a40 100644
--- a/libmaple/adc.c
+++ b/libmaple/adc.c
@@ -126,8 +126,8 @@ void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate) {
* @param dev adc device
*/
static void adc_calibrate(const adc_dev *dev) {
- __io uint32 *rstcal_bit = (__io uint32*)BITBAND_PERI(&(dev->regs->CR2), 3);
- __io uint32 *cal_bit = (__io uint32*)BITBAND_PERI(&(dev->regs->CR2), 2);
+ __io uint32 *rstcal_bit = bb_peripv(&(dev->regs->CR2), 3);
+ __io uint32 *cal_bit = bb_peripv(&(dev->regs->CR2), 2);
*rstcal_bit = 1;
while (*rstcal_bit)
diff --git a/libmaple/adc.h b/libmaple/adc.h
index ac386fb..4811dbc 100644
--- a/libmaple/adc.h
+++ b/libmaple/adc.h
@@ -30,14 +30,16 @@
#ifndef _ADC_H_
#define _ADC_H_
-#include "util.h"
+#include "libmaple.h"
+#include "bitband.h"
#include "rcc.h"
#ifdef __cplusplus
extern "C"{
#endif
+/** ADC register map type. */
typedef struct adc_reg_map {
__io uint32 SR; ///< Status register
__io uint32 CR1; ///< Control register 1
@@ -61,22 +63,30 @@ typedef struct adc_reg_map {
__io uint32 DR; ///< Regular data register
} adc_reg_map;
+/** ADC device type. */
typedef struct adc_dev {
- adc_reg_map *regs;
- rcc_clk_id clk_id;
+ adc_reg_map *regs; /**< Register map */
+ rcc_clk_id clk_id; /**< RCC clock information */
} adc_dev;
+/** ADC1 device. */
extern const adc_dev *ADC1;
+/** ADC2 device. */
extern const adc_dev *ADC2;
#ifdef STM32_HIGH_DENSITY
+/** ADC3 device. */
extern const adc_dev *ADC3;
#endif
/*
* ADC peripheral base addresses
*/
+
+/** ADC1 register map base pointer. */
#define ADC1_BASE ((adc_reg_map*)0x40012400)
+/** ADC2 register map base pointer. */
#define ADC2_BASE ((adc_reg_map*)0x40012800)
+/** ADC3 register map base pointer. */
#define ADC3_BASE ((adc_reg_map*)0x40013C00)
/*
@@ -138,8 +148,8 @@ void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate);
/**
* @brief Perform a single synchronous software triggered conversion on a
- * channel
- * @param regs ADC register map
+ * channel.
+ * @param dev ADC device to use for reading.
* @param channel channel to convert
* @return conversion result
*/
@@ -161,27 +171,27 @@ static inline uint32 adc_read(const adc_dev *dev, uint8 channel) {
/**
* @brief Set external trigger conversion mode event for regular channels
- * @param dev adc device
- * @param enable if 1, conversion on external events is enabled, 0 to disable
+ * @param dev ADC device
+ * @param enable If 1, conversion on external events is enabled, 0 to disable
*/
static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) {
- __write(BITBAND_PERI(&(dev->regs->CR2), 20), enable);
+ *bb_peripv(&dev->regs->CR2, 20) = !!enable;
}
/**
* @brief Enable an adc peripheral
- * @param regs register map of peripheral to enable
+ * @param dev ADC device to enable
*/
static inline void adc_enable(const adc_dev *dev) {
- __write(BITBAND_PERI(&(dev->regs->CR2), 0), 1);
+ *bb_peripv(&dev->regs->CR2, 0) = 1;
}
/**
- * @brief Disable an adc peripheral
- * @param regs register map of peripheral to disable
+ * @brief Disable an ADC peripheral
+ * @param dev ADC device to disable
*/
static inline void adc_disable(const adc_dev *dev) {
- __write(BITBAND_PERI(&(dev->regs->CR2), 0), 0);
+ *bb_peripv(&dev->regs->CR2, 0) = 0;
}
/**
@@ -198,5 +208,5 @@ static inline void adc_disable_all(void) {
#ifdef __cplusplus
} // extern "C"
#endif
-#endif
+#endif
diff --git a/libmaple/bitband.h b/libmaple/bitband.h
new file mode 100644
index 0000000..076335f
--- /dev/null
+++ b/libmaple/bitband.h
@@ -0,0 +1,83 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * 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 bitband.h
+ *
+ * @brief Bit-banding utility functions
+ */
+
+#define BB_SRAM_REF 0x20000000
+#define BB_SRAM_BASE 0x22000000
+#define BB_PERI_REF 0x40000000
+#define BB_PERI_BASE 0x42000000
+
+static inline uint32* __bb_addr(void*, uint32, uint32, uint32);
+static inline __io uint32* __bb_addrv(__io void*, uint32, uint32, uint32);
+
+/**
+ * @brief Obtain a pointer to the bit-band address corresponding to a
+ * bit in an SRAM address.
+ * @param address Address in the bit-banded SRAM region
+ * @param bit Bit in address to bit-band
+ */
+static inline uint32* bb_sramp(void *address, uint32 bit) {
+ return __bb_addr(address, bit, BB_SRAM_BASE, BB_SRAM_REF);
+}
+
+/**
+ * @brief Obtain a pointer to the bit-band address corresponding to a
+ * bit in a volatile SRAM address.
+ * @param address Address in the bit-banded SRAM region
+ * @param bit Bit in address to bit-band
+ */
+static inline __io uint32* bb_srampv(__io void *address, uint32 bit) {
+ return __bb_addrv(address, bit, BB_SRAM_BASE, BB_SRAM_REF);
+}
+
+/**
+ * @brief Obtain a pointer to the bit-band address corresponding to a
+ * bit in a peripheral address.
+ * @param address Address in the bit-banded peripheral region
+ * @param bit Bit in address to bit-band
+ */
+static inline __io uint32* bb_peripv(__io void *address, uint32 bit) {
+ return __bb_addrv(address, bit, BB_PERI_BASE, BB_PERI_REF);
+}
+
+static inline uint32* __bb_addr(void *address,
+ uint32 bit,
+ uint32 bb_base,
+ uint32 bb_ref) {
+ return (uint32*)(bb_base + ((uint32)address - bb_ref) * 32 + bit * 4);
+}
+
+static inline __io uint32* __bb_addrv(__io void *address,
+ uint32 bit,
+ uint32 bb_base,
+ uint32 bb_ref) {
+ return (__io uint32*)__bb_addr((void*)address, bit, bb_base, bb_ref);
+}
diff --git a/libmaple/bkp.c b/libmaple/bkp.c
index ed107d8..b152069 100644
--- a/libmaple/bkp.c
+++ b/libmaple/bkp.c
@@ -27,7 +27,7 @@
#include "bkp.h"
#include "pwr.h"
#include "rcc.h"
-#include "util.h"
+#include "bitband.h"
static inline __io uint32* data_register(uint8 reg);
@@ -57,14 +57,14 @@ void bkp_init(void) {
* @see bkp_init()
*/
void bkp_enable_writes(void) {
- __write(BITBAND_PERI(&(PWR_BASE->CR), PWR_CR_DBP), 1);
+ *bb_peripv(&PWR_BASE->CR, PWR_CR_DBP) = 1;
}
/**
* Disable write access to the backup registers.
*/
void bkp_disable_writes(void) {
- __write(BITBAND_PERI(&(PWR_BASE->CR), PWR_CR_DBP), 0);
+ *bb_peripv(&PWR_BASE->CR, PWR_CR_DBP) = 0;
}
/**
diff --git a/libmaple/bkp.h b/libmaple/bkp.h
index 96ef8d2..cea39b6 100644
--- a/libmaple/bkp.h
+++ b/libmaple/bkp.h
@@ -44,6 +44,7 @@ extern "C" {
#define BKP_NR_DATA_REGS 42
#endif
+/** Backup peripheral register map type. */
typedef struct bkp_reg_map {
const uint32 RESERVED1;
__io uint32 DR1; ///< Data register 1
@@ -97,20 +98,17 @@ typedef struct bkp_reg_map {
#endif
} bkp_reg_map;
+/** Backup peripheral register map base pointer. */
+#define BKP_BASE ((bkp_reg_map*)0x40006C00)
+
+/** Backup peripheral device type. */
typedef struct bkp_dev {
- bkp_reg_map *regs;
+ bkp_reg_map *regs; /**< Register map */
} bkp_dev;
-/**
- * Backup device.
- */
+/** Backup device. */
extern const bkp_dev *BKP;
-/*
- * Backup peripheral base.
- */
-#define BKP_BASE ((bkp_reg_map*)0x40006C00)
-
void bkp_init(void);
void bkp_enable_writes(void);
void bkp_disable_writes(void);
diff --git a/libmaple/dac.c b/libmaple/dac.c
index 54b555b..ef3a9f9 100644
--- a/libmaple/dac.c
+++ b/libmaple/dac.c
@@ -80,15 +80,15 @@ void dac_write_channel(uint8 channel, uint16 val) {
void dac_enable_channel(uint8 channel) {
/*
* Setup ANALOG mode on PA4 and PA5. This mapping is consistent across
- * all STM32 chips with a DAC. See RM008 12.2.
+ * all STM32 chips with a DAC. See RM0008 12.2.
*/
switch (channel) {
case 1:
- gpio_set_mode(GPIOA_BASE, 4, GPIO_MODE_INPUT_ANALOG);
+ gpio_set_mode(GPIOA, 4, GPIO_INPUT_ANALOG);
DAC->regs->CR |= DAC_CR_EN1;
break;
case 2:
- gpio_set_mode(GPIOA_BASE, 5, GPIO_MODE_INPUT_ANALOG);
+ gpio_set_mode(GPIOA, 5, GPIO_INPUT_ANALOG);
DAC->regs->CR |= DAC_CR_EN2;
break;
}
diff --git a/libmaple/dac.h b/libmaple/dac.h
index bc64324..c897bb2 100644
--- a/libmaple/dac.h
+++ b/libmaple/dac.h
@@ -25,9 +25,10 @@
/**
* @file dac.h
* @brief Digital to analog converter header file
- * See notes/dac.txt for more info
*/
+/* See notes/dac.txt for more info */
+
#ifndef _DAC_H_
#define _DAC_H_
@@ -63,16 +64,15 @@ typedef struct dac_reg_map {
__io uint32 DOR2; /**< Channel 2 data output register */
} dac_reg_map;
+/** DAC device type. */
typedef struct dac_dev {
- dac_reg_map *regs;
+ dac_reg_map *regs; /**< Register map */
} dac_dev;
/** DAC device. */
extern const dac_dev *DAC;
-/*
- * DAC peripheral base address
- */
+/** DAC register map base address */
#define DAC_BASE ((dac_reg_map*)0x40007400)
/*
diff --git a/libmaple/exti.c b/libmaple/exti.c
index e8ad52a..8177e1e 100644
--- a/libmaple/exti.c
+++ b/libmaple/exti.c
@@ -23,19 +23,29 @@
*****************************************************************************/
/**
+ * @file exti.c
* @brief External interrupt control routines
*/
#include "libmaple.h"
#include "exti.h"
#include "nvic.h"
+#include "bitband.h"
-typedef struct ExtIChannel {
+/*
+ * Internal state
+ */
+
+/* Status bitmaps, for external interrupts with multiplexed IRQs */
+static uint16 exti_9_5_en = 0;
+static uint16 exti_15_10_en = 0;
+
+typedef struct exti_channel {
void (*handler)(void);
uint32 irq_line;
-} ExtIChannel;
+} exti_channel;
-static ExtIChannel exti_channels[] = {
+static exti_channel exti_channels[] = {
{ .handler = NULL, .irq_line = NVIC_EXTI0 }, // EXTI0
{ .handler = NULL, .irq_line = NVIC_EXTI1 }, // EXTI1
{ .handler = NULL, .irq_line = NVIC_EXTI2 }, // EXTI2
@@ -54,63 +64,127 @@ static ExtIChannel exti_channels[] = {
{ .handler = NULL, .irq_line = NVIC_EXTI15_10 }, // EXTI15
};
-static inline void clear_pending(int bit) {
- __set_bits(EXTI_PR, BIT(bit));
- /* If the pending bit is cleared as the last instruction in an ISR,
- * it won't actually be cleared in time and the ISR will fire again.
- * Insert a 2-cycle buffer to allow it to take effect. */
- asm volatile("nop");
- asm volatile("nop");
-}
+/*
+ * Convenience routines
+ */
+
+static inline void enable_irq(afio_exti_num exti_num);
+static inline void maybe_disable_irq(afio_exti_num exti_num);
+
+/**
+ * @brief Register a handler to run upon external interrupt.
+ *
+ * This function assumes that the interrupt request corresponding to
+ * the given external interrupt is masked.
+ *
+ * @param num External interrupt line number.
+ * @param port Port to use as source input for external interrupt.
+ * @param handler Function handler to execute when interrupt is triggered.
+ * @param mode Type of transition to trigger on, one of:
+ * EXTI_RISING, EXTI_FALLING, EXTI_RISING_FALLING.
+ * @see exti_num
+ * @see exti_port
+ * @see exti_trigger_mode
+ */
+void exti_attach_interrupt(afio_exti_num num,
+ afio_exti_port port,
+ voidFuncPtr handler,
+ exti_trigger_mode mode) {
+ ASSERT(handler);
-static inline void dispatch_handler(uint32 channel) {
- ASSERT(exti_channels[channel].handler);
- if (exti_channels[channel].handler) {
- (exti_channels[channel].handler)();
+ /* Register the handler */
+ exti_channels[num].handler = handler;
+
+ /* Set trigger mode */
+ switch (mode) {
+ case EXTI_RISING:
+ *bb_peripv(&EXTI_BASE->RTSR, num) = 1;
+ break;
+ case EXTI_FALLING:
+ *bb_peripv(&EXTI_BASE->FTSR, num) = 1;
+ break;
+ case EXTI_RISING_FALLING:
+ *bb_peripv(&EXTI_BASE->RTSR, num) = 1;
+ *bb_peripv(&EXTI_BASE->FTSR, num) = 1;
+ break;
}
+
+ /* Map num to port */
+ afio_exti_select(num, port);
+
+ /* Unmask external interrupt request */
+ *bb_peripv(&EXTI_BASE->IMR, num) = 1;
+
+ /* Enable the interrupt line */
+ enable_irq(num);
+}
+
+/**
+ * @brief Unregister an external interrupt handler
+ * @param num Number of the external interrupt line to disable.
+ * @see exti_num
+ */
+void exti_detach_interrupt(afio_exti_num num) {
+ /* First, mask the interrupt request */
+ *bb_peripv(&EXTI_BASE->IMR, num) = 0;
+
+ /* Then, clear the trigger selection registers */
+ *bb_peripv(&EXTI_BASE->FTSR, num) = 0;
+ *bb_peripv(&EXTI_BASE->RTSR, num) = 0;
+
+ /* Next, disable the IRQ, unless it's multiplexed and there are
+ * other active external interrupts on the same IRQ line */
+ maybe_disable_irq(num);
+
+ /* Finally, unregister the user's handler */
+ exti_channels[num].handler = NULL;
}
-/* For EXTI0 through EXTI4, only one handler
- * is associated with each channel, so we
- * don't have to keep track of which channel
+/*
+ * Interrupt handlers
+ */
+
+static inline void clear_pending(uint32 exti_num);
+static inline void dispatch_handler(uint32 exti_num);
+
+/* For AFIO_EXTI_0 through AFIO_EXTI_4, only one handler is associated
+ * with each channel, so we don't have to keep track of which channel
* we came from */
void __irq_exti0(void) {
- dispatch_handler(EXTI0);
- clear_pending(EXTI0);
+ dispatch_handler(AFIO_EXTI_0);
+ clear_pending(AFIO_EXTI_0);
}
void __irq_exti1(void) {
- dispatch_handler(EXTI1);
- clear_pending(EXTI1);
+ dispatch_handler(AFIO_EXTI_1);
+ clear_pending(AFIO_EXTI_1);
}
void __irq_exti2(void) {
- dispatch_handler(EXTI2);
- clear_pending(EXTI2);
+ dispatch_handler(AFIO_EXTI_2);
+ clear_pending(AFIO_EXTI_2);
}
void __irq_exti3(void) {
- dispatch_handler(EXTI3);
- clear_pending(EXTI3);
+ dispatch_handler(AFIO_EXTI_3);
+ clear_pending(AFIO_EXTI_3);
}
void __irq_exti4(void) {
- dispatch_handler(EXTI4);
- clear_pending(EXTI4);
+ dispatch_handler(AFIO_EXTI_4);
+ clear_pending(AFIO_EXTI_4);
}
void __irq_exti9_5(void) {
/* Figure out which channel it came from */
- uint32 pending;
+ uint32 pending = GET_BITS(EXTI_BASE->PR, 5, 9);
uint32 i;
- pending = REG_GET(EXTI_PR);
- pending = GET_BITS(pending, 5, 9);
/* Dispatch every handler if the pending bit is set */
for (i = 0; i < 5; i++) {
if (pending & 0x1) {
- dispatch_handler(EXTI5 + i);
- clear_pending(EXTI5 + i);
+ dispatch_handler(AFIO_EXTI_5 + i);
+ clear_pending(AFIO_EXTI_5 + i);
}
pending >>= 1;
}
@@ -118,89 +192,59 @@ void __irq_exti9_5(void) {
void __irq_exti15_10(void) {
/* Figure out which channel it came from */
- uint32 pending;
+ uint32 pending = GET_BITS(EXTI_BASE->PR, 10, 15);
uint32 i;
- pending = REG_GET(EXTI_PR);
- pending = GET_BITS(pending, 10, 15);
/* Dispatch every handler if the pending bit is set */
for (i = 0; i < 6; i++) {
if (pending & 0x1) {
- dispatch_handler(EXTI10 + i);
- clear_pending(EXTI10 + i);
+ dispatch_handler(AFIO_EXTI_10 + i);
+ clear_pending(AFIO_EXTI_10 + i);
}
pending >>= 1;
}
}
-
-/**
- * @brief Register a handler to run upon external interrupt
- * @param port source port of pin (eg EXTI_CONFIG_PORTA)
- * @param pin pin number on the source port
- * @param handler function handler to execute
- * @param mode type of transition to trigger on
+/*
+ * Auxiliary functions
*/
-void exti_attach_interrupt(uint32 port,
- uint32 pin,
- voidFuncPtr handler,
- uint32 mode) {
- static uint32 afio_regs[] = {
- AFIO_EXTICR1, // EXT0-3
- AFIO_EXTICR2, // EXT4-7
- AFIO_EXTICR3, // EXT8-11
- AFIO_EXTICR4, // EXT12-15
- };
-
- /* Note: All of the following code assumes that EXTI0 = 0 */
- ASSERT(EXTI0 == 0);
- ASSERT(handler);
-
- uint32 channel = pin;
- /* map port to channel */
- __write(afio_regs[pin/4], (port << ((pin % 4) * 4)));
-
- /* Unmask appropriate interrupt line */
- __set_bits(EXTI_IMR, BIT(channel));
-
- /* Set trigger mode */
- switch (mode) {
- case EXTI_RISING:
- __set_bits(EXTI_RTSR, BIT(channel));
- break;
-
- case EXTI_FALLING:
- __set_bits(EXTI_FTSR, BIT(channel));
- break;
+static inline void clear_pending(uint32 exti_num) {
+ *bb_peripv(&EXTI_BASE->PR, exti_num) = 1;
+ /* If the pending bit is cleared as the last instruction in an ISR,
+ * it won't actually be cleared in time and the ISR will fire again.
+ * Insert a 2-cycle buffer to allow it to take effect. */
+ asm volatile("nop");
+ asm volatile("nop");
+}
- case EXTI_RISING_FALLING:
- __set_bits(EXTI_RTSR, BIT(channel));
- __set_bits(EXTI_FTSR, BIT(channel));
- break;
+static inline void dispatch_handler(uint32 exti_num) {
+ ASSERT(exti_channels[exti_num].handler);
+ if (exti_channels[exti_num].handler) {
+ (exti_channels[exti_num].handler)();
}
-
- /* Register the handler */
- exti_channels[channel].handler = handler;
-
- /* Configure the enable interrupt bits for the NVIC */
- nvic_irq_enable(exti_channels[channel].irq_line);
}
+static inline void enable_irq(afio_exti_num exti) {
+ /* Maybe twiddle the IRQ bitmap for extis with multiplexed IRQs */
+ if (exti > 4) {
+ uint16 *bitmap = exti < 10 ? &exti_9_5_en : &exti_15_10_en;
+ *bb_sramp(bitmap, exti) = 1;
+ }
-/**
- * @brief Unregister an external interrupt handler
- * @param channel channel to disable (eg EXTI0)
- */
-void exti_detach_interrupt(uint32 channel) {
- ASSERT(channel < NR_EXTI_CHANNELS);
- ASSERT(EXTI0 == 0);
-
- __clear_bits(EXTI_IMR, BIT(channel));
- __clear_bits(EXTI_FTSR, BIT(channel));
- __clear_bits(EXTI_RTSR, BIT(channel));
-
- nvic_irq_disable(exti_channels[channel].irq_line);
+ nvic_irq_enable(exti_channels[exti].irq_line);
+}
- exti_channels[channel].handler = NULL;
+static inline void maybe_disable_irq(afio_exti_num exti) {
+ if (exti > 4) {
+ uint16 *bitmap = exti < 10 ? &exti_9_5_en : &exti_15_10_en;
+ *bb_sramp(bitmap, exti) = 0;
+ if (*bitmap == 0) {
+ /* All of the external interrupts which share this IRQ
+ * line are disabled. */
+ nvic_irq_disable(exti_channels[exti].irq_line);
+ }
+ } else {
+ nvic_irq_disable(exti_channels[exti].irq_line);
+ }
}
diff --git a/libmaple/exti.h b/libmaple/exti.h
index 806578f..e145033 100644
--- a/libmaple/exti.h
+++ b/libmaple/exti.h
@@ -22,145 +22,51 @@
* THE SOFTWARE.
*****************************************************************************/
-
/**
- * @file exti.h
- *
- * @brief External interrupt control prototypes and defines
+ * @file exti.h
+ * @brief External interrupt control prototypes and defines
*/
-#ifndef _EXTI_H_
-#define _EXTI_H_
-
-/* Notes:
- *
- * To generate the interrupt, the interrupt line should be configured
- * and enabled. This is done by programming the two trigger registers
- * with the desired edge detection and by enabling the interrupt
- * request by writing a '1' to the corresponding bit in the interrupt
- * mask register. When the selected edge occurs on the external
- * interrupt line, an interrupt request is generated. The pending bit
- * corresponding to the interrupt line is also set. This request is
- * reset by writing a '1' in the pending register.
- *
- * Hardware interrupt selection:
- *
- * To configure the 20 lines as interrupt sources, use the following
- * procedure:
- *
- * 1) Configure AFIO_EXTIICR[y] to select the source input for EXTIx
- * external interrupt
- * 2) Configure the mask bits of the 20 interrupt lines (EXTI_IMR)
- * 3) Configure the trigger selection bits of the interrupt lines
- * (EXTI_RTSR and EXTI_FTSR)
- * 4) Configure the enable and mask bits that control the NVIC_IRQ
- * channel mapped to the External
- *
- * Interrupt Controller (EXTI) so that an inerrupt coming from one of
- * the 20 lines can be correctly acknowledged.
- *
- * AFIO clock must be on.
- *
- * RM0008, page 107: "PD0, PD1 cannot be used for external
- * interrupt/event generation on 36, 48, 64-bin packages."
- *
- * ----------------------------------------------------------------------------
- * Pin to EXTI Line Mappings:
- * EXTI0 EXTI1 EXTI2 EXTI3 EXTI4
- * --------------------------------------------------------------------------
- * D2/PA0 D3/PA1 D1/PA2 D0/A6/PA3 D10/A10/PA4
- * D26/EXT7/PB0 D27/EXT8/PB1 D16/A2/PC2 D17/A3/PC3 D18/A4/PC4
- * D14/A0/PC0 D15/PC1 D25/EXT5/PD2
- *
- * EXTI5 EXTI6 EXTI7 EXTI8 EXTI9
- * ----------------------------------------------------------------------------
- * D13/A13/PA5 D12/A12/PA6 D11/A11/PA7 D6/PA8 D7/PA9
- * D4/PB5 D5/PB6 D9/PB7 D38/PB8 D23/EXT4/PB9
- * D19/A5/PC5 D34/EXTI15/PC6 D35/EXT16/PC7 D36/PC8 D37/EXT18/PC9
- *
- * EXTI10 EXTI11 EXTI12 EXTI13 EXTI14
- * ----------------------------------------------------------------------------
- * D8/PA10 D29/EXT10/PB11 D30/EXTI1/PB12 D31/EXTI12/PB13 D32/EXT13/PB14
- * D28/PB10 D20/EXTI1/PC13 D21/EXT2/PC14
- * D25/PC10
- *
- * EXTI15
- * ----------------------------------------------------------------------------
- * D33/EXTI14/PB15
- * D22/EXT3/PC15
- *
- *
- * The 16 EXTI interrupts are mapped to 7 interrupt handlers.
- *
- * EXTI Lines to Interrupt Mapping:
- * EXTI0 -> EXTI0
- * EXTI1 -> EXTI1
- * EXTI2 -> EXTI2
- * EXTI3 -> EXTI3
- * EXTI4 -> EXTI4
- * EXTI[5-9] -> EXT9_5
- * EXTI[10-15] -> EXT15_10
- *
- * */
-
-#define NR_EXTI_MODES 3
-#define NR_EXTI_CHANNELS 16
-#define NR_EXTI_PORTS NR_GPIO_PORTS // board specific
+/* See notes/exti.txt for more info */
-#define EXTI_RISING 0
-#define EXTI_FALLING 1
-#define EXTI_RISING_FALLING 2
+#include "libmaple.h"
+#include "gpio.h"
-#define EXTI_IMR 0x40010400 // Interrupt mask register
-#define EXTI_EMR (EXTI_IMR + 0x04) // Event mask register
-#define EXTI_RTSR (EXTI_IMR + 0x08) // Rising trigger selection register
-#define EXTI_FTSR (EXTI_IMR + 0x0C) // Falling trigger selection register
-#define EXTI_SWIER (EXTI_IMR + 0x10) // Software interrupt event register
-#define EXTI_PR (EXTI_IMR + 0x14) // Pending register
-
-#define AFIO_EVCR 0x40010000
-#define AFIO_EXTICR1 (AFIO_EVCR + 0x08)
-#define AFIO_EXTICR2 (AFIO_EVCR + 0x0C)
-#define AFIO_EXTICR3 (AFIO_EVCR + 0x10)
-#define AFIO_EXTICR4 (AFIO_EVCR + 0x14)
-
-#define EXTI0 0
-#define EXTI1 1
-#define EXTI2 2
-#define EXTI3 3
-#define EXTI4 4
-#define EXTI5 5
-#define EXTI6 6
-#define EXTI7 7
-#define EXTI8 8
-#define EXTI9 9
-#define EXTI10 10
-#define EXTI11 11
-#define EXTI12 12
-#define EXTI13 13
-#define EXTI14 14
-#define EXTI15 15
-
-#define EXTI_CONFIG_PORTA 0 // Maple, Maple Native, Maple Mini
-#define EXTI_CONFIG_PORTB 1 // Maple, Maple Native, Maple Mini
-#define EXTI_CONFIG_PORTC 2 // Maple, Maple Native, Maple Mini
-#define EXTI_CONFIG_PORTD 3 // Maple and Maple Native only
-#define EXTI_CONFIG_PORTE 4 // Native only
-#define EXTI_CONFIG_PORTF 5 // Native only
-#define EXTI_CONFIG_PORTG 6 // Native only
+#ifndef _EXTI_H_
+#define _EXTI_H_
#ifdef __cplusplus
extern "C"{
#endif
-void exti_attach_interrupt(uint32 port, uint32 pin, voidFuncPtr handler,
- uint32 mode);
-void exti_detach_interrupt(uint32 channel);
+/** EXTI register map type */
+typedef struct exti_reg_map {
+ __io uint32 IMR; /**< Interrupt mask register */
+ __io uint32 EMR; /**< Event mask register */
+ __io uint32 RTSR; /**< Rising trigger selection register */
+ __io uint32 FTSR; /**< Falling trigger selection register */
+ __io uint32 SWIER; /**< Software interrupt event register */
+ __io uint32 PR; /**< Pending register */
+} exti_reg_map;
+
+/** EXTI register map base pointer */
+#define EXTI_BASE ((exti_reg_map*)0x40010400)
+
+/** External interrupt trigger mode */
+typedef enum exti_trigger_mode {
+ EXTI_RISING, /**< Trigger on the rising edge */
+ EXTI_FALLING, /**< Trigger on the falling edge */
+ EXTI_RISING_FALLING /**< Trigger on both the rising and falling edges */
+} exti_trigger_mode;
+
+void exti_attach_interrupt(afio_exti_num num,
+ afio_exti_port port,
+ voidFuncPtr handler,
+ exti_trigger_mode mode);
+void exti_detach_interrupt(afio_exti_num num);
#ifdef __cplusplus
} // extern "C"
#endif
-
#endif
-
diff --git a/libmaple/fsmc.c b/libmaple/fsmc.c
index 49526f4..1561add 100644
--- a/libmaple/fsmc.c
+++ b/libmaple/fsmc.c
@@ -31,6 +31,8 @@
#include "gpio.h"
#include "fsmc.h"
+#ifdef STM32_HIGH_DENSITY
+
/* These values determined for a particular SRAM chip by following the
* calculations in the ST FSMC application note. */
#define FSMC_ADDSET 0x0
@@ -45,55 +47,55 @@ void fsmc_native_sram_init(void) {
/* First we setup all the GPIO pins. */
/* Data lines... */
- gpio_set_mode(GPIOD_BASE, 0, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOD_BASE, 1, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOD_BASE, 8, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOD_BASE, 9, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOD_BASE, 10, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOD_BASE, 14, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOD_BASE, 15, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOE_BASE, 7, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOE_BASE, 8, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOE_BASE, 9, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOE_BASE, 10, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOE_BASE, 11, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOE_BASE, 12, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOE_BASE, 13, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOE_BASE, 14, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOE_BASE, 15, MODE_AF_OUTPUT_PP);
+ 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_BASE, 11, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOD_BASE, 12, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOD_BASE, 13, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOF_BASE, 0, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOF_BASE, 1, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOF_BASE, 2, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOF_BASE, 3, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOF_BASE, 4, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOF_BASE, 5, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOF_BASE, 12, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOF_BASE, 13, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOF_BASE, 14, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOF_BASE, 15, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOG_BASE, 0, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOG_BASE, 1, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOG_BASE, 2, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOG_BASE, 3, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOG_BASE, 4, MODE_AF_OUTPUT_PP);
- gpio_set_mode(GPIOG_BASE, 5, MODE_AF_OUTPUT_PP);
+ 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_BASE, 4, MODE_AF_OUTPUT_PP); // NOE
- gpio_set_mode(GPIOD_BASE, 5, MODE_AF_OUTPUT_PP); // NWE
+ gpio_set_mode(GPIOD, 4, GPIO_AF_OUTPUT_PP); // NOE
+ gpio_set_mode(GPIOD, 5, GPIO_AF_OUTPUT_PP); // NWE
- gpio_set_mode(GPIOD_BASE, 7, MODE_AF_OUTPUT_PP); // NE1
- gpio_set_mode(GPIOG_BASE, 9, MODE_AF_OUTPUT_PP); // NE2
- gpio_set_mode(GPIOG_BASE, 10, MODE_AF_OUTPUT_PP); // NE3
- gpio_set_mode(GPIOG_BASE, 12, MODE_AF_OUTPUT_PP); // NE4
+ 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_BASE, 0, MODE_AF_OUTPUT_PP); // NBL0
- gpio_set_mode(GPIOE_BASE, 1, MODE_AF_OUTPUT_PP); // NBL1
+ gpio_set_mode(GPIOE, 0, GPIO_AF_OUTPUT_PP); // NBL0
+ gpio_set_mode(GPIOE, 1, GPIO_AF_OUTPUT_PP); // NBL1
/* Next enable the clock */
rcc_clk_enable(RCC_FSMC);
@@ -132,3 +134,4 @@ void fsmc_native_sram_init(void) {
/* (FSMC_BWTR3 not used for this simple configuration.) */
}
+#endif /* STM32_HIGH_DENSITY */
diff --git a/libmaple/fsmc.h b/libmaple/fsmc.h
index e83b529..fed6894 100644
--- a/libmaple/fsmc.h
+++ b/libmaple/fsmc.h
@@ -37,6 +37,8 @@
extern "C"{
#endif
+#ifdef STM32_HIGH_DENSITY
+
// There are 4 FSMC chip-select devices; here are the SRAM-specific registers
// for each
@@ -82,9 +84,10 @@ typedef struct {
void fsmc_native_sram_init(void);
+#endif /* STM32_HIGH_DENSITY */
+
#ifdef __cplusplus
} // extern "C"
#endif
-
#endif
diff --git a/libmaple/gpio.c b/libmaple/gpio.c
index 71e5230..b08be12 100644
--- a/libmaple/gpio.c
+++ b/libmaple/gpio.c
@@ -26,44 +26,151 @@
* @brief GPIO initialization routine
*/
-#include "libmaple.h"
-#include "rcc.h"
#include "gpio.h"
+#include "rcc.h"
+
+/*
+ * GPIO devices
+ */
+
+static gpio_dev gpioa = {
+ .regs = GPIOA_BASE,
+ .clk_id = RCC_GPIOA
+};
+/** GPIO port A device. */
+gpio_dev *GPIOA = &gpioa;
+
+static gpio_dev gpiob = {
+ .regs = GPIOB_BASE,
+ .clk_id = RCC_GPIOB
+};
+/** GPIO port B device. */
+gpio_dev *GPIOB = &gpiob;
+
+static gpio_dev gpioc = {
+ .regs = GPIOC_BASE,
+ .clk_id = RCC_GPIOC
+};
+/** GPIO port C device. */
+gpio_dev *GPIOC = &gpioc;
+
+static gpio_dev gpiod = {
+ .regs = GPIOD_BASE,
+ .clk_id = RCC_GPIOD
+};
+/** GPIO port D device. */
+gpio_dev *GPIOD = &gpiod;
+
+#ifdef STM32_HIGH_
+static gpio_dev gpioe = {
+ .regs = GPIOE_BASE,
+ .clk_id = RCC_GPIOE
+};
+/** GPIO port E device. */
+gpio_dev *GPIOE = &gpioe;
+
+static gpio_dev gpiof = {
+ .regs = GPIOF_BASE,
+ .clk_id = RCC_GPIOF
+};
+/** GPIO port F device. */
+gpio_dev *GPIOF = &gpiof;
-void gpio_init(void) {
- rcc_clk_enable(RCC_GPIOA);
- rcc_clk_enable(RCC_GPIOB);
- rcc_clk_enable(RCC_GPIOC);
-#if NR_GPIO_PORTS >= 4 /* Maple, but not Maple Mini */
- rcc_clk_enable(RCC_GPIOD);
-#elif NR_GPIO_PORTS >= 7 /* Maple Native (high density only) */
- rcc_clk_enable(RCC_GPIOE);
- rcc_clk_enable(RCC_GPIOF);
- rcc_clk_enable(RCC_GPIOG);
+static gpio_dev gpiog = {
+ .regs = GPIOG_BASE,
+ .clk_id = RCC_GPIOG
+};
+/** GPIO port G device. */
+gpio_dev *GPIOG = &gpiog;
#endif
- rcc_clk_enable(RCC_AFIO);
+
+/*
+ * GPIO convenience routines
+ */
+
+/**
+ * Initialize a GPIO device.
+ *
+ * Enables the clock for and resets the given device.
+ *
+ * @param dev GPIO device to initialize.
+ */
+void gpio_init(gpio_dev *dev) {
+ rcc_clk_enable(dev->clk_id);
+ rcc_reset_dev(dev->clk_id);
}
-void gpio_set_mode(GPIO_Port* port, uint8 gpio_pin, GPIOPinMode mode) {
- uint32 tmp;
- uint32 shift = POS(gpio_pin % 8);
- GPIOReg CR;
+/**
+ * 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
+}
- ASSERT(port);
- ASSERT(gpio_pin < 16);
+/**
+ * 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_MODE_INPUT_PU) {
- port->ODR |= BIT(gpio_pin);
- mode = CNF_INPUT_PD;
- } else if (mode == GPIO_MODE_INPUT_PD) {
- port->ODR &= ~BIT(gpio_pin);
+ if (mode == GPIO_INPUT_PD) {
+ regs->ODR &= ~BIT(pin);
+ } else if (mode == GPIO_INPUT_PU) {
+ regs->ODR |= BIT(pin);
}
+}
+
+/*
+ * AFIO
+ */
- CR = (gpio_pin < 8) ? &(port->CRL) : &(port->CRH);
+/**
+ * Initialize the AFIO clock, and reset the AFIO registers.
+ */
+void afio_init(void) {
+ rcc_clk_enable(RCC_AFIO);
+ rcc_reset_dev(RCC_AFIO);
+}
- tmp = *CR;
- tmp &= POS_MASK(shift);
- tmp |= mode << shift;
+#define AFIO_EXTI_SEL_MASK 0xF
+
+/**
+ * Select a source input for an external interrupt.
+ *
+ * @param exti External interrupt. One of: AFIO_EXTI_0,
+ * AFIO_EXTI_1, ..., AFIO_EXTI_15.
+ * @param gpio_port Port which contains pin to use as source input.
+ * One of: AFIO_EXTI_PA, AFIO_EXTI_PB, AFIO_EXTI_PC,
+ * AFIO_EXTI_PD, and, on high density devices,
+ * AFIO_EXTI_PE, AFIO_EXTI_PF, AFIO_EXTI_PG.
+ * @see exti_port
+ */
+void afio_exti_select(afio_exti_num exti, afio_exti_port gpio_port) {
+ __io uint32 *exti_cr = &AFIO_BASE->EXTICR1 + exti / 4;
+ uint32 shift = 4 * (exti % 4);
+ uint32 cr = *exti_cr;
- *CR = tmp;
+ cr &= ~(AFIO_EXTI_SEL_MASK << shift);
+ cr |= gpio_port << shift;
+ *exti_cr = cr;
}
diff --git a/libmaple/gpio.h b/libmaple/gpio.h
index 53f77c4..48dbc00 100644
--- a/libmaple/gpio.h
+++ b/libmaple/gpio.h
@@ -3,126 +3,331 @@
*
* 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
+ * 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 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.
+ * 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 gpio.h
*
- * @brief GPIO prototypes, defines, and inlined access functions
+ * @brief General purpose I/0 (GPIO) and Alternate Function I/O
+ * (AFIO) prototypes, defines, and inlined access functions.
*/
-#ifndef _GPIO_H
-#define _GPIO_H
-
-/* Each of the GPIO port bits can be in the following modes (STM32 138/995):
- * Input floating
- * Input pull-up
- * Input pull-down
- * Analog Input
- * Output open-drain
- * Output push-pull
- * Alternate function push-pull
- * Alternate function open-drain
- *
- * - After reset, the alternate functions are not active and IO prts
- * are set to Input Floating mode, EXCEPT for the Serial Wire and JTAG
- * ports, which are in alternate function mode by default. */
-
-#define AFIO_MAPR ((volatile uint32*)0x40010004)
-
-#define GPIOA_BASE ((GPIO_Port*)0x40010800)
-#define GPIOB_BASE ((GPIO_Port*)0x40010C00)
-#define GPIOC_BASE ((GPIO_Port*)0x40011000)
-#define GPIOD_BASE ((GPIO_Port*)0x40011400)
-#define GPIOE_BASE ((GPIO_Port*)0x40011800) // High-density devices only
-#define GPIOF_BASE ((GPIO_Port*)0x40011C00) // High-density devices only
-#define GPIOG_BASE ((GPIO_Port*)0x40012000) // High-density devices only
-
-#define GPIO_SPEED_50MHZ (0x3)
-
-#define MODE_OUTPUT_PP ((0x00 << 2) | GPIO_SPEED_50MHZ)
-#define MODE_OUTPUT_OD ((0x01 << 2) | GPIO_SPEED_50MHZ)
-#define MODE_AF_OUTPUT_PP ((0x02 << 2) | GPIO_SPEED_50MHZ)
-#define MODE_AF_OUTPUT_OD ((0x03 << 2) | GPIO_SPEED_50MHZ)
-
-#define CNF_INPUT_ANALOG (0x00 << 2)
-#define CNF_INPUT_FLOATING (0x01 << 2)
-#define CNF_INPUT_PD (0x02 << 2)
-#define CNF_INPUT_PU (0x02 << 2)
-
-typedef enum GPIOPinMode {
- GPIO_MODE_OUTPUT_PP = MODE_OUTPUT_PP,
- GPIO_MODE_OUTPUT_OD = MODE_OUTPUT_OD,
- GPIO_MODE_AF_OUTPUT_PP = MODE_AF_OUTPUT_PP,
- GPIO_MODE_AF_OUTPUT_OD = MODE_AF_OUTPUT_OD,
- GPIO_MODE_INPUT_ANALOG = CNF_INPUT_ANALOG,
- GPIO_MODE_INPUT_FLOATING = CNF_INPUT_FLOATING,
- GPIO_MODE_INPUT_PD = CNF_INPUT_PD,
- GPIO_MODE_INPUT_PU,
-} GPIOPinMode;
-
-typedef struct {
- volatile uint32 CRL; // Port configuration register low
- volatile uint32 CRH; // Port configuration register high
- volatile uint32 IDR; // Port input data register
- volatile uint32 ODR; // Port output data register
- volatile uint32 BSRR; // Port bit set/reset register
- volatile uint32 BRR; // Port bit reset register
- volatile uint32 LCKR; // Port configuration lock register
-} GPIO_Port;
-
-typedef volatile uint32* GPIOReg;
-
-#define POS_MASK(shift) (~(0xF << shift))
-#define POS(val) (val << 2)
+#ifndef _GPIO_H_
+#define _GPIO_H_
+
+#include "libmaple.h"
+#include "rcc.h"
#ifdef __cplusplus
extern "C"{
#endif
-void gpio_init(void);
-void gpio_set_mode(GPIO_Port* port, uint8 gpio_pin, GPIOPinMode mode);
+/*
+ * 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;
+
+/** GPIO device type */
+typedef struct gpio_dev {
+ gpio_reg_map *regs; ///< Register map
+ rcc_clk_id clk_id; ///< RCC clock information
+} gpio_dev;
+
+/** GPIO port A device */
+extern gpio_dev *GPIOA;
+/** GPIO port B device */
+extern gpio_dev *GPIOB;
+/** GPIO port C device */
+extern gpio_dev *GPIOC;
+/** GPIO port D device */
+extern gpio_dev *GPIOD;
+#ifdef STM32_HIGH_DENSITY
+/** GPIO port E device */
+extern gpio_dev *GPIOE;
+/** GPIO port F device */
+extern gpio_dev *GPIOF;
+/** GPIO port G device */
+extern gpio_dev *GPIOG;
+#endif
+
+/** GPIO port A register map base pointer */
+#define GPIOA_BASE ((gpio_reg_map*)0x40010800)
+/** GPIO port B register map base pointer */
+#define GPIOB_BASE ((gpio_reg_map*)0x40010C00)
+/** GPIO port C register map base pointer */
+#define GPIOC_BASE ((gpio_reg_map*)0x40011000)
+/** GPIO port D register map base pointer */
+#define GPIOD_BASE ((gpio_reg_map*)0x40011400)
+#ifdef STM32_HIGH_DENSITY
+/** GPIO port E register map base pointer */
+#define GPIOE_BASE ((gpio_reg_map*)0x40011800)
+/** GPIO port F register map base pointer */
+#define GPIOF_BASE ((gpio_reg_map*)0x40011C00)
+/** GPIO port G register map base pointer */
+#define GPIOG_BASE ((gpio_reg_map*)0x40012000)
+#endif
+
+/*
+ * GPIO register bit definitions
+ */
+
+/* Control registers, low and high */
+#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_INPUT 0x0
+#define GPIO_CR_MODE_OUTPUT_10MHZ 0x1
+#define GPIO_CR_MODE_OUTPUT_2MHZ 0x2
+#define GPIO_CR_MODE_OUTPUT_50MHZ 0x3
+
+/** GPIO Pin modes. These only allow for 50MHZ max output speeds; if
+ * you want slower, use direct register access. */
+typedef enum gpio_pin_mode {
+ GPIO_OUTPUT_PP = (GPIO_CR_CNF_OUTPUT_PP |
+ GPIO_CR_MODE_OUTPUT_50MHZ), /**< Output push-pull. */
+ GPIO_OUTPUT_OD = (GPIO_CR_CNF_OUTPUT_OD |
+ GPIO_CR_MODE_OUTPUT_50MHZ), /**< Output open-drain. */
+ GPIO_AF_OUTPUT_PP = (GPIO_CR_CNF_AF_OUTPUT_PP |
+ GPIO_CR_MODE_OUTPUT_50MHZ), /**< Alternate function
+ output push-pull. */
+ GPIO_AF_OUTPUT_OD = (GPIO_CR_CNF_AF_OUTPUT_OD |
+ GPIO_CR_MODE_OUTPUT_50MHZ), /**< Alternate function
+ output open drain. */
+ GPIO_INPUT_ANALOG = (GPIO_CR_CNF_INPUT_ANALOG |
+ GPIO_CR_MODE_INPUT), /**< Analog input. */
+ GPIO_INPUT_FLOATING = (GPIO_CR_CNF_INPUT_FLOATING |
+ GPIO_CR_MODE_INPUT), /**< Input floating. */
+ GPIO_INPUT_PD = (GPIO_CR_CNF_INPUT_PU_PD |
+ GPIO_CR_MODE_INPUT), /**< Input pull-down. */
+ GPIO_INPUT_PU /**< Input pull-up. */
+ /* GPIO_INPUT_PU treated as a special case, for ODR twiddling */
+} gpio_pin_mode;
-static inline void gpio_write_bit(GPIO_Port *port, uint8 gpio_pin, uint8 val) {
- if (val){
- port->BSRR = BIT(gpio_pin);
+/*
+ * GPIO Convenience routines
+ */
+
+void gpio_init(gpio_dev *dev);
+void gpio_init_all(void);
+void gpio_set_mode(gpio_dev *dev, uint8 pin, gpio_pin_mode mode);
+
+/**
+ * Set or reset a GPIO pin.
+ *
+ * Pin must have previously been configured to output mode.
+ *
+ * @param dev GPIO device whose pin to set.
+ * @param pin Pin on to set or reset
+ * @param val If true, set the pin. If false, reset the pin.
+ */
+static inline void gpio_write_bit(gpio_dev *dev, uint8 pin, uint8 val) {
+ if (val) {
+ dev->regs->BSRR = BIT(pin);
} else {
- port->BRR = BIT(gpio_pin);
+ dev->regs->BRR = BIT(pin);
}
}
-static inline uint32 gpio_read_bit(GPIO_Port *port, uint8 gpio_pin) {
- return (port->IDR & BIT(gpio_pin) ? 1 : 0);
+/**
+ * Determine whether or not a GPIO pin is set.
+ *
+ * Pin must have previously been configured to input mode.
+ *
+ * @param dev GPIO device whose pin to test.
+ * @param pin Pin on dev to test.
+ * @return True if the pin is set, false otherwise.
+ */
+static inline uint32 gpio_read_bit(gpio_dev *dev, uint8 pin) {
+ return dev->regs->IDR & BIT(pin);
}
-/* For pins configured as output push-pull, reading the ODR returns
- * the last value written in push-pull mode.
+/**
+ * Toggle a pin configured as output push-pull.
+ * @param dev GPIO device.
+ * @param pin Pin on dev to toggle.
*/
-static inline void gpio_toggle_pin(GPIO_Port *port, uint8 gpio_pin) {
- port->ODR = port->ODR ^ BIT(gpio_pin);
+static inline void gpio_toggle_bit(gpio_dev *dev, uint8 pin) {
+ dev->regs->ODR = dev->regs->ODR ^ BIT(pin);
}
-#ifdef __cplusplus
-} // extern "C"
+/*
+ * 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 ((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_FULL_SWJ (0x0 << 24)
+#define AFIO_MAPR_SWJ_FULL_SWJ_NO_NJRST (0x1 << 24)
+#define AFIO_MAPR_SWJ_NO_JTAG_SW (0x2 << 24)
+#define AFIO_MAPR_SWJ_NO_JTAG_NO_SW (0x4 << 24)
+#define AFIO_MAPR_ADC2_ETRGREG_REMAP BIT(20)
+#define AFIO_MAPR_ADC2_ETRGINJ_REMAP BIT(19)
+#define AFIO_MAPR_ADC1_ETRGREG_REMAP BIT(18)
+#define AFIO_MAPR_ADC1_ETRGINJ_REMAP BIT(17)
+#define AFIO_MAPR_TIM5CH4_IREMAP BIT(16)
+#define AFIO_MAPR_PD01_REMAP BIT(15)
+#define AFIO_MAPR_CAN_REMAP (BIT(14) | BIT(13))
+#define AFIO_MAPR_TIM4_REMAP_FULL BIT(12)
+#define AFIO_MAPR_TIM3_REMAP (BIT(11) | BIT(10))
+#define AFIO_MAPR_TIM2_REMAP (BIT(9) | BIT(8))
+#define AFIO_MAPR_TIM1_REMAP (BIT(7) | BIT(6))
+#define AFIO_MAPR_USART3_REMAP (BIT(5) | BIT(4))
+#define AFIO_MAPR_USART2_REMAP BIT(3)
+#define AFIO_MAPR_USART1_REMAP BIT(2)
+#define AFIO_MAPR_I2C1_REMAP BIT(1)
+#define AFIO_MAPR_SPI1_REMAP BIT(0)
+
+/* External interrupt configuration registers */
+
+/**
+ * External interrupt line port selector. Used to determine which
+ * GPIO port to map an external interrupt line onto. */
+typedef enum {
+ AFIO_EXTI_PA, /**< Use PAx pin. */
+ AFIO_EXTI_PB, /**< Use PBx pin. */
+ AFIO_EXTI_PC, /**< Use PCx pin. */
+ AFIO_EXTI_PD, /**< Use PDx pin. */
+#ifdef STM32_HIGH_DENSITY
+ AFIO_EXTI_PE, /**< Use PEx pin. */
+ AFIO_EXTI_PF, /**< Use PFx pin. */
+ AFIO_EXTI_PG, /**< Use PGx pin. */
#endif
+} afio_exti_port;
+
+/**
+ * External interrupt line numbers.
+ */
+typedef enum {
+ AFIO_EXTI_0, /**< External interrupt line 0. */
+ AFIO_EXTI_1, /**< External interrupt line 1. */
+ AFIO_EXTI_2, /**< External interrupt line 2. */
+ AFIO_EXTI_3, /**< External interrupt line 3. */
+ AFIO_EXTI_4, /**< External interrupt line 4. */
+ AFIO_EXTI_5, /**< External interrupt line 5. */
+ AFIO_EXTI_6, /**< External interrupt line 6. */
+ AFIO_EXTI_7, /**< External interrupt line 7. */
+ AFIO_EXTI_8, /**< External interrupt line 8. */
+ AFIO_EXTI_9, /**< External interrupt line 9. */
+ AFIO_EXTI_10, /**< External interrupt line 10. */
+ AFIO_EXTI_11, /**< External interrupt line 11. */
+ AFIO_EXTI_12, /**< External interrupt line 12. */
+ AFIO_EXTI_13, /**< External interrupt line 13. */
+ AFIO_EXTI_14, /**< External interrupt line 14. */
+ AFIO_EXTI_15, /**< External interrupt line 15. */
+} afio_exti_num;
+/* AF remap and debug I/O configuration register 2 */
+#define AFIO_MAPR2_FSMC_NADV BIT(10)
+#define AFIO_MAPR2_TIM14_REMAP BIT(9)
+#define AFIO_MAPR2_TIM13_REMAP BIT(8)
+#define AFIO_MAPR2_TIM11_REMAP BIT(7)
+#define AFIO_MAPR2_TIM10_REMAP BIT(6)
+#define AFIO_MAPR2_TIM9_REMAP BIT(5)
+
+/*
+ * AFIO convenience routines
+ */
+
+void afio_init(void);
+void afio_exti_select(afio_exti_num exti, afio_exti_port gpio_port);
+
+/**
+ * Set the SWJ_CONFIG bits in the AFIO MAPR register.
+ *
+ * @param config Desired SWJ_CONFIG bits setting. One of:
+ * AFIO_MAPR_SWJ_FULL_SWJ (full SWJ),
+ * AFIO_MAPR_SWJ_FULL_SWJ_NO_NJRST (full SWJ, no NJTRST),
+ * AFIO_MAPR_SWJ_NO_JTAG_SW (JTAG-DP disabled, SW-DP enabled),
+ * AFIO_MAPR_SWJ_NO_JTAG_NO_SW (JTAG-DP and SW-DP both disabled).
+ */
+static inline void afio_mapr_swj_config(uint32 config) {
+ __io uint32 *mapr = &AFIO_BASE->MAPR;
+ *mapr = (*mapr & ~(0x7 << 24)) | config;
+}
+
+#ifdef __cplusplus
+}
+#endif
#endif
diff --git a/libmaple/libmaple.h b/libmaple/libmaple.h
index 6b75c96..0bbd34e 100644
--- a/libmaple/libmaple.h
+++ b/libmaple/libmaple.h
@@ -36,7 +36,7 @@
/*
* Where to put usercode, based on space reserved for bootloader.
*
- * FIXME this has no business being here
+ * FIXME this has no business being here
*/
#define USER_ADDR_ROM 0x08005000
#define USER_ADDR_RAM 0x20000C00
diff --git a/libmaple/libmaple_types.h b/libmaple/libmaple_types.h
index a976a9e..54bef65 100644
--- a/libmaple/libmaple_types.h
+++ b/libmaple/libmaple_types.h
@@ -44,6 +44,7 @@ typedef long long int64;
typedef void (*voidFuncPtr)(void);
#define __io volatile
+#define __attr_flash __attribute__((section (".USER_FLASH")))
#ifndef NULL
#define NULL 0
diff --git a/libmaple/pwr.h b/libmaple/pwr.h
index 5ff815d..5f68c34 100644
--- a/libmaple/pwr.h
+++ b/libmaple/pwr.h
@@ -41,20 +41,19 @@ typedef struct pwr_reg_map {
__io uint32 CSR; /**< Control and status register */
} pwr_reg_map;
-/*
- * Power peripheral base.
- */
+/** Power peripheral register map base pointer. */
#define PWR_BASE ((pwr_reg_map*)0x40007000)
-/** Power interface device. */
+/** Power device type. */
typedef struct pwr_dev {
- pwr_reg_map *regs;
+ pwr_reg_map *regs; /**< Register map */
} pwr_dev;
/**
* Power device.
*/
extern const pwr_dev *PWR;
+
/*
* Register bit definitions
*/
diff --git a/libmaple/rcc.h b/libmaple/rcc.h
index 410ab8b..8697e01 100644
--- a/libmaple/rcc.h
+++ b/libmaple/rcc.h
@@ -27,6 +27,8 @@
* @brief reset and clock control definitions and prototypes
*/
+#include "libmaple_types.h"
+
#ifndef _RCC_H_
#define _RCC_H_
@@ -182,7 +184,6 @@ typedef enum {
RCC_BKP,
} rcc_clk_id;
-
void rcc_clk_init(uint32 sysclk_src, uint32 pll_src, uint32 pll_mul);
void rcc_clk_enable(rcc_clk_id device);
void rcc_reset_dev(rcc_clk_id device);
diff --git a/libmaple/ring_buffer.h b/libmaple/ring_buffer.h
index a44088e..f7baa6c 100644
--- a/libmaple/ring_buffer.h
+++ b/libmaple/ring_buffer.h
@@ -13,21 +13,20 @@
extern "C"{
#endif
-/* The buffer is empty when head == tail.
+/**
+ * Ring buffer type.
+ *
+ * The buffer is empty when head == tail.
*
* The buffer is full when the head is one byte in front of the tail,
* modulo buffer length.
*
* One byte is left free to distinguish empty from full. */
typedef struct ring_buffer {
- /** Buffer items are stored into */
- volatile uint8 *buf;
- /** Index of the next item to remove */
- uint16 head;
- /** Index where the next item will get inserted */
- uint16 tail;
- /** Buffer capacity minus one */
- uint16 size;
+ volatile uint8 *buf; /**< Buffer items are stored into */
+ uint16 head; /**< Index of the next item to remove */
+ uint16 tail; /**< Index where the next item will get inserted */
+ uint16 size; /**< Buffer capacity minus one */
} ring_buffer;
/**
diff --git a/libmaple/spi.c b/libmaple/spi.c
index 8bba0d6..7bdc18a 100644
--- a/libmaple/spi.c
+++ b/libmaple/spi.c
@@ -43,23 +43,23 @@
typedef struct spi_dev {
SPI *base;
- GPIO_Port *port;
+ gpio_dev *gpio_d;
uint8 sck_pin;
uint8 miso_pin;
uint8 mosi_pin;
} spi_dev;
-static const spi_dev spi_dev1 = {
+spi_dev spi_dev1 = {
.base = (SPI*)SPI1_BASE,
- .port = GPIOA_BASE,
+ .gpio_d = NULL,
.sck_pin = 5,
.miso_pin = 6,
.mosi_pin = 7
};
-static const spi_dev spi_dev2 = {
+spi_dev spi_dev2 = {
.base = (SPI*)SPI2_BASE,
- .port = GPIOB_BASE,
+ .gpio_d = NULL,
.sck_pin = 13,
.miso_pin = 14,
.mosi_pin = 15
@@ -90,11 +90,13 @@ void spi_init(uint32 spi_num,
ASSERT(prescale != CR1_BR_PRESCALE_2);
spi = (SPI*)SPI1_BASE;
rcc_clk_enable(RCC_SPI1);
+ spi_dev1.gpio_d = GPIOA;
spi_gpio_cfg(&spi_dev1);
break;
case 2:
spi = (SPI*)SPI2_BASE;
rcc_clk_enable(RCC_SPI2);
+ spi_dev1.gpio_d = GPIOB,
spi_gpio_cfg(&spi_dev2);
break;
}
@@ -155,7 +157,7 @@ uint8 spi_tx(uint32 spi_num, uint8 *buf, uint32 len) {
}
static void spi_gpio_cfg(const spi_dev *dev) {
- gpio_set_mode(dev->port, dev->sck_pin, GPIO_MODE_AF_OUTPUT_PP);
- gpio_set_mode(dev->port, dev->miso_pin, GPIO_MODE_AF_OUTPUT_PP);
- gpio_set_mode(dev->port, dev->mosi_pin, GPIO_MODE_AF_OUTPUT_PP);
+ gpio_set_mode(dev->gpio_d, dev->sck_pin, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(dev->gpio_d, dev->miso_pin, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(dev->gpio_d, dev->mosi_pin, GPIO_AF_OUTPUT_PP);
}
diff --git a/libmaple/usb/usb.c b/libmaple/usb/usb.c
index 62f56fc..2fc4eb2 100644
--- a/libmaple/usb/usb.c
+++ b/libmaple/usb/usb.c
@@ -44,7 +44,7 @@
volatile uint32 bDeviceState = UNCONNECTED;
volatile uint16 wIstr = 0;
-volatile bIntPackSOF = 0;
+volatile uint32 bIntPackSOF = 0;
DEVICE Device_Table =
{NUM_ENDPTS,
@@ -99,15 +99,13 @@ struct {
} ResumeS;
void setupUSB (void) {
- gpio_set_mode(USB_DISC_BANK,
- USB_DISC_PIN,
- GPIO_MODE_OUTPUT_PP);
+ gpio_set_mode(USB_DISC_DEV, USB_DISC_PIN, GPIO_OUTPUT_PP);
/* setup the apb1 clock for USB */
pRCC->APB1ENR |= 0x00800000;
/* initialize the usb application */
- gpio_write_bit(USB_DISC_BANK, USB_DISC_PIN, 0); // presents us to the host
+ gpio_write_bit(USB_DISC_DEV, USB_DISC_PIN, 0); // presents us to the host
USB_Init(); // low level init routine provided by the ST library
}
@@ -115,7 +113,7 @@ void disableUSB (void) {
// These are just guesses about how to do this
// TODO: real disable function
usbDsbISR();
- gpio_write_bit(USB_DISC_BANK,USB_DISC_PIN,1);
+ gpio_write_bit(USB_DISC_DEV, USB_DISC_PIN, 1);
}
void usbSuspend(void) {
@@ -320,8 +318,29 @@ if (wIstr & ISTR_CTR & wInterrupt_Mask) {
}
+static void FIXME_delayMicroseconds_copy(uint32 us) {
+ /* So (2^32)/12 micros max, or less than 6 minutes */
+ us *= 12;
+
+ /* fudge for function call overhead */
+ us--;
+ asm volatile(" mov r0, %[us] \n\t"
+ "1: subs r0, #1 \n\t"
+ " bhi 1b \n\t"
+ :
+ : [us] "r" (us)
+ : "r0");
+}
+
+static void FIXME_delay_copy(unsigned long ms) {
+ uint32 i;
+ for (i = 0; i < ms; i++) {
+ FIXME_delayMicroseconds_copy(1000);
+ }
+}
+
void usbWaitReset(void) {
- delay(RESET_DELAY);
+ FIXME_delay_copy(RESET_DELAY);
systemHardReset();
}
diff --git a/libmaple/usb/usb_callbacks.c b/libmaple/usb/usb_callbacks.c
index ccb0fdd..8184537 100644
--- a/libmaple/usb/usb_callbacks.c
+++ b/libmaple/usb/usb_callbacks.c
@@ -129,7 +129,7 @@ u8* vcomGetSetLineCoding(uint16 length) {
return (uint8*)&line_coding;
}
-vcomSetLineState(void) {
+void vcomSetLineState(void) {
}
void usbInit(void) {
diff --git a/libmaple/usb/usb_config.h b/libmaple/usb/usb_config.h
index 394c580..9003da9 100644
--- a/libmaple/usb/usb_config.h
+++ b/libmaple/usb/usb_config.h
@@ -4,6 +4,7 @@
#define __USB_CONFIG_H
#include "usb_lib.h"
+#include "gpio.h"
/******************************************************************************
******************************************************************************
@@ -31,19 +32,19 @@
/* USB Identifier numbers */
#define VCOM_ID_PRODUCT 0x0004
- #define USB_DISC_BANK GPIOC_BASE
+ #define USB_DISC_DEV GPIOC
#define USB_DISC_PIN 12
#elif defined(BOARD_maple_mini)
#define VCOM_ID_PRODUCT 0x0005
- #define USB_DISC_BANK GPIOB_BASE
+ #define USB_DISC_DEV GPIOB
#define USB_DISC_PIN 9
#elif defined(BOARD_maple_native)
#define VCOM_ID_PRODUCT 0x0006
- #define USB_DISC_BANK GPIOB_BASE
+ #define USB_DISC_DEV GPIOB
#define USB_DISC_PIN 8
#else
diff --git a/libmaple/usb/usb_hardware.c b/libmaple/usb/usb_hardware.c
index 505dcf1..9a7d12c 100644
--- a/libmaple/usb/usb_hardware.c
+++ b/libmaple/usb/usb_hardware.c
@@ -33,47 +33,6 @@
#include "usb_hardware.h"
-void setPin(u32 bank, u8 pin) {
- u32 pinMask = 0x1 << (pin);
- SET_REG(GPIO_BSRR(bank),pinMask);
-}
-
-void resetPin(u32 bank, u8 pin) {
- u32 pinMask = 0x1 << (16+pin);
- SET_REG(GPIO_BSRR(bank),pinMask);
-}
-
-void systemReset(void) {
- SET_REG(RCC_CR, GET_REG(RCC_CR) | 0x00000001);
- SET_REG(RCC_CFGR, GET_REG(RCC_CFGR) & 0xF8FF0000);
- SET_REG(RCC_CR, GET_REG(RCC_CR) & 0xFEF6FFFF);
- SET_REG(RCC_CR, GET_REG(RCC_CR) & 0xFFFBFFFF);
- SET_REG(RCC_CFGR, GET_REG(RCC_CFGR) & 0xFF80FFFF);
-
- SET_REG(RCC_CIR, 0x00000000); // disable all RCC interrupts
-}
-
-void setupCLK (void) {
- /* enable HSE */
- SET_REG(RCC_CR,GET_REG(RCC_CR) | 0x00010001);
- /* for it to come on */
- while ((GET_REG(RCC_CR) & 0x00020000) == 0);
-
- /* Configure PLL */
- /* pll=72Mhz,APB1=36Mhz,AHB=72Mhz */
- SET_REG(RCC_CFGR,GET_REG(RCC_CFGR) | 0x001D0400);
- /* enable the pll */
- SET_REG(RCC_CR,GET_REG(RCC_CR) | 0x01000000);
- /* wait for it to come on */
- while ((GET_REG(RCC_CR) & 0x03000000) == 0);
-
- /* Set SYSCLK as PLL */
- SET_REG(RCC_CFGR,GET_REG(RCC_CFGR) | 0x00000002);
- /* wait for it to come on */
- while ((GET_REG(RCC_CFGR) & 0x00000008) == 0);
-}
-
-
void nvicInit(NVIC_InitTypeDef* NVIC_InitStruct) {
u32 tmppriority = 0x00;
u32 tmpreg = 0x00;
diff --git a/libmaple/usb/usb_hardware.h b/libmaple/usb/usb_hardware.h
index e4a26b4..cfead1a 100644
--- a/libmaple/usb/usb_hardware.h
+++ b/libmaple/usb/usb_hardware.h
@@ -22,34 +22,20 @@
* THE SOFTWARE.
* ****************************************************************************/
-#ifndef __HARDWARE_H
-#define __HARDWARE_H
-
+#include "rcc.h"
#include "usb_type.h"
+#ifndef _USB_HARDWARE_H_
+#define _USB_HARDWARE_H_
+
/* macro'd register and peripheral definitions */
#define EXC_RETURN 0xFFFFFFF9
#define DEFAULT_CPSR 0x61000000
-#define RCC ((u32)0x40021000)
#define FLASH ((u32)0x40022000)
-#define GPIOA ((u32)0x40010800)
-#define GPIOC ((u32)0x40011000)
#define USB_PACKET_BUFFER ((u32)0x40006000)
-#define RCC_CR RCC
-#define RCC_CFGR RCC + 0x04
-#define RCC_CIR RCC + 0x08
-#define RCC_AHBENR RCC + 0x14
-#define RCC_APB2ENR RCC + 0x18
-#define RCC_APB1ENR RCC + 0x16
-
-#define GPIO_CRL(port) port
-#define GPIO_CRH(port) port+0x04
-#define GPIO_ODR(port) port+0x0c
-#define GPIO_BSRR(port) port+0x10
-
#define SCS_BASE ((u32)0xE000E000)
#define NVIC_BASE (SCS_BASE + 0x0100)
#define SCB_BASE (SCS_BASE + 0x0D00)
@@ -74,9 +60,8 @@
#define __PSC(__TIMCLK, __PERIOD) (((__VAL(__TIMCLK, __PERIOD)+49999UL)/50000UL) - 1)
#define __ARR(__TIMCLK, __PERIOD) ((__VAL(__TIMCLK, __PERIOD)/(__PSC(__TIMCLK, __PERIOD)+1)) - 1)
-/* todo, wrap in do whiles for the natural ; */
-#define SET_REG(addr,val) *(vu32*)(addr)=val
-#define GET_REG(addr) *(vu32*)(addr)
+#define SET_REG(addr,val) do { *(vu32*)(addr)=val; } while (0)
+#define GET_REG(addr) do { *(vu32*)(addr); } while (0)
#if defined(__cplusplus)
extern "C" {
@@ -85,7 +70,7 @@ extern "C" {
/* todo: there must be some major misunderstanding in how we access regs. The direct access approach (GET_REG)
causes the usb init to fail upon trying to activate RCC_APB1 |= 0x00800000. However, using the struct approach
from ST, it works fine...temporarily switching to that approach */
-typedef struct
+typedef struct
{
vu32 CR;
vu32 CFGR;
@@ -98,7 +83,7 @@ typedef struct
vu32 BDCR;
vu32 CSR;
} RCC_RegStruct;
-#define pRCC ((RCC_RegStruct *) RCC)
+#define pRCC ((RCC_RegStruct *) RCC_BASE)
typedef struct {
vu32 ISER[2];
@@ -139,12 +124,7 @@ typedef struct {
} SCB_TypeDef;
-void setPin (u32 bank, u8 pin);
-void resetPin (u32 bank, u8 pin);
-
void systemHardReset(void);
-void systemReset (void);
-void setupCLK (void);
void nvicInit (NVIC_InitTypeDef*);
void nvicDisableInterrupts(void);
diff --git a/libmaple/util.c b/libmaple/util.c
index 3408a2e..09fbecd 100644
--- a/libmaple/util.c
+++ b/libmaple/util.c
@@ -38,7 +38,7 @@
#ifndef ERROR_USART_NUM
#define ERROR_USART_NUM USART2
#define ERROR_USART_BAUD 9600
-#define ERROR_TX_PORT GPIOA_BASE
+#define ERROR_TX_PORT GPIOA
#define ERROR_TX_PIN 2
#endif
@@ -87,7 +87,7 @@ void __error(void) {
*/
void _fail(const char* file, int line, const char* exp) {
/* Initialize the error usart */
- gpio_set_mode(ERROR_TX_PORT, ERROR_TX_PIN, GPIO_MODE_AF_OUTPUT_PP);
+ gpio_set_mode(ERROR_TX_PORT, ERROR_TX_PIN, GPIO_AF_OUTPUT_PP);
usart_init(ERROR_USART_NUM, ERROR_USART_BAUD);
/* Print failed assert message */
@@ -116,7 +116,7 @@ void throb(void) {
uint32 TOP_CNT = 0x0200;
uint32 i = 0;
- gpio_set_mode(ERROR_LED_PORT, ERROR_LED_PIN, GPIO_MODE_OUTPUT_PP);
+ gpio_set_mode(ERROR_LED_PORT, ERROR_LED_PIN, GPIO_OUTPUT_PP);
/* Error fade */
while (1) {
if (CC == TOP_CNT) {
diff --git a/libmaple/util.h b/libmaple/util.h
index fb524c2..25dd56e 100644
--- a/libmaple/util.h
+++ b/libmaple/util.h
@@ -28,6 +28,8 @@
* @brief Various macros and utility procedures.
*/
+#include "libmaple_types.h"
+
/* Generally "useful" utility procedures */
#ifndef _UTIL_H_
#define _UTIL_H_
@@ -51,40 +53,29 @@ extern "C"{
/* Return bits m to n of x */
#define GET_BITS(x, m, n) ((((uint32)x) << (31 - (n))) >> ((31 - (n)) + (m)))
-/* Bit-banding macros */
-/* Bitbanded Memory sections */
-#define BITBAND_SRAM_REF 0x20000000
-#define BITBAND_SRAM_BASE 0x22000000
-#define BITBAND_PERI_REF 0x40000000
-#define BITBAND_PERI_BASE 0x42000000
-/* Convert SRAM address */
-#define BITBAND_SRAM(a,b) ((BITBAND_SRAM_BASE+(a-BITBAND_SRAM_REF)*32+(b*4)))
-/* Convert peripheral address */
-#define BITBAND_PERI(a, b) ((BITBAND_PERI_BASE + \
- ((uint32)a - BITBAND_PERI_REF) * 32 + (b * 4)))
-
-#define REG_SET(reg, val) (*(volatile uint32*)(reg) = (val))
-#define REG_SET_BIT(reg, bit) (*(volatile uint32*)(reg) |= BIT(bit))
-#define REG_CLEAR_BIT(reg, bit) (*(volatile uint32*)(reg) &= ~BIT(bit))
-#define REG_SET_MASK(reg, mask) (*(volatile uint32*)(reg) |= (uint32)(mask))
-#define REG_CLEAR_MASK(reg, mask) (*(volatile uint32*)(reg) &= (uint32)~(mask))
-
-#define REG_GET(reg) (*(volatile uint32*)(reg))
+/*
+ * Register reads and writes
+ */
#define __set_bits(addr, mask) (*(volatile uint32*)(addr) |= (uint32)(mask))
#define __clear_bits(addr, mask) (*(volatile uint32*)(addr) &= (uint32)~(mask))
#define __get_bits(addr, mask) (*(volatile uint32*)(addr) & (uint32)(mask))
-
#define __read(reg) (*(volatile uint32*)(reg))
#define __write(reg, value) (*(volatile uint32*)(reg) = (value))
#define IS_POWER_OF_TWO(v) (v && !(v & (v - 1)))
+
+/*
+ * Failure routines
+ */
+
void __error(void);
void _fail(const char*, int, const char*);
void throb(void);
-/* Asserts for sanity checks, redefine DEBUG_LEVEL in libmaple.h to
- * compile out these checks */
+/*
+ * Asserts and debug levels
+ */
#if DEBUG_LEVEL >= DEBUG_ALL
#define ASSERT(exp) \
diff --git a/notes/coding_standard.txt b/notes/coding_standard.txt
index 5cb96c3..372ebf4 100644
--- a/notes/coding_standard.txt
+++ b/notes/coding_standard.txt
@@ -25,12 +25,11 @@ License
-------
- Put an MIT license at the beginning of the file (look at any of our
- source files for an example). Copyright should go to either you or
- LeafLabs LLC.
+ source files for an example). Copyright should go either to you or
+ to LeafLabs, LLC.
Emacs: if you don't like seeing the license, you should use
- elide-head (which will hide it for you). Here is some elisp you can
- modify to make this pleasant:
+ elide-head (which will hide it for you). You can use the following:
(require 'elide-head)
(setq programming-mode-hooks '(c-mode-hook c++-mode-hook))
@@ -38,7 +37,7 @@ License
'("The MIT License" . "DEALINGS IN\n [*] THE SOFTWARE"))
(add-to-list 'elide-head-headers-to-hide
'("The MIT License" . "DEALINGS IN THE\n...SOFTWARE"))
- (dolist (hook mbolivar-programming-mode-hooks)
+ (dolist (hook programming-mode-hooks)
(add-hook hook (lambda () (elide-head))))
Whitespace/Indentation
@@ -46,7 +45,8 @@ Whitespace/Indentation
- 4 space indents. [Set in .dir-locals.el]
-- Unix newlines.
+- Unix newlines. [Some exceptions are currently grandfathered in;
+ these will go away in time.]
- No tab characters. [Set in .dir-locals.el]
@@ -76,50 +76,53 @@ Whitespace/Indentation
(add-hook 'c-mode-hook c-mode-inextern-lang-hook)
-
Comments
--------
-- Multi-line comments look like this:
+- Multi-line comments are pretty flexible. Any of these is fine:
- /* text starts here
- * continued lines have a '*' before them
- * the comment can end after the last line
+ /* Comment starts here.
+ * Continued lines have a '*' before them.
+ * The comment can end after the last line.
*/
- or this:
-
- /* comment starts here
- * the comment can end on the same line */
+ /* Comment starts here.
+ * The comment can end on the same line. */
-- Doxygen comments are newline comments that begin with /** instead.
- It is not required that the "/**" appear on a line by itself.
+ /*
+ * You can also place a newline after the opening "/*".
+ */
-- Single-line comments on the same line are // in c or c++.
+- Doxygen comments are multi-line comments that begin with /** instead.
-- Single-line comments on their own source line are /* */ in c, but
- can also be // in c++. If you think that typing out /* */ is too
- slow in emacs, use M-; (comment-dwim) when you're on an empty line,
- and it'll ... well...
+- Single-line comments on the same line are // in C or C++.
- You should be using the (super awesome) comment-dwim; it pretty
- much does exactly what you want to the comment on the current
- line, including "create one and put it in the right place".
+- Single-line comments on their own source line should be /* */ in C,
+ but can also be // in C++. In Emacs, you can use M-;
+ (comment-dwim), and it'll Do What You Mean.
Braces
------
-- 1TBS. Nothing more need be said.
+- Mostly 1TBS:
http://en.wikipedia.org/wiki/Indent_style#Variant:_1TBS
+ The only difference is that the opening brace of a function's
+ definition occurs exactly one space character after the closing
+ parenthesis in that function's parameter list. Example:
+
+ void func(void) {
+ ...
+ }
+
Naming conventions
------------------
-- There's always a fight about upper and lower case vs. underscores.
- We'll handle this as follows.
+There's always a fight about upper and lower case vs. underscores.
+We'll handle this as follows.
- First, Dammit_Dont_Mix_Like_This, because It_Looks_Really_Ugly, ok?
+- First, Dammit_Dont_Mix_Like_This, because It_Looks_Really_Ugly, ok?
[There's been some debate about this, and some exceptions are
already grandfathered in, so in order to settle it, let's call this
a "recommendation" instead of "requirement".]
@@ -168,7 +171,7 @@ Naming conventions
Documentation
-------------
-- Document your code. This should go without saying.
+- Document your code!
- For complicated peripherals, it would be nice if you put longer-form
comments into this directory (notes/), with a comment in the
@@ -176,13 +179,8 @@ Documentation
example. That lets us keep the source files relatively clean while
still allowing new readers to have a starting point.
-- At least put a doxygen comment with a nonempty @brief for every .h
- file you add. See the existing ones for examples. For now, it'd be
- better if you didn't put a @brief into any .c[pp] files, since it
- (currently) interferes with our documentation generator in a way
- that I won't explain here (though you can look into the LeafLabs or
- michaeljones breathe repos on github and potentially figure out
- why).
+- At least put a Doxygen comment with a nonempty @brief for every .h
+ file you add. See the existing ones for examples.
- Doxygen comments generally just belong on types, functions,
etc. that are part of the public user-facing API. This generally
@@ -196,8 +194,13 @@ Documentation
This should be avoided if at all possible, since it creates a
maintenance burden of documenting things in two places at once, and
- provides an opportunity for bad documentation to slip in, when the
- code comments fall out of sync with the ReST docs.
+ makes it easier for documentation to go stale.
+
+- For libmaple proper (the pure C library under libmaple/); the
+ convention is to document any user-facing entity at the point where
+ it is defined. In particular, this means you should document an
+ externally-linked function defined in a .c file in that .c file, not
+ in the header file where it is declared to the user.
General Formatting
------------------
@@ -217,7 +220,3 @@ General Formatting
(require 'lineker)
(dolist (hook '(c-mode-hook c++-mode-hook))
(add-hook hook (lambda () (lineker-mode 1))))
-
- There are only a few exceptional situations. The most important one
- is when specifying a lookup table like PIN_MAP where it'd be ugly to
- split each entry over multiple lines.
diff --git a/notes/exti.txt b/notes/exti.txt
new file mode 100644
index 0000000..1ad49ee
--- /dev/null
+++ b/notes/exti.txt
@@ -0,0 +1,67 @@
+External interrupt notes.
+
+To generate the interrupt, the interrupt line should be configured
+and enabled. This is done by programming the two trigger registers
+with the desired edge detection and by enabling the interrupt
+request by writing a '1' to the corresponding bit in the interrupt
+mask register. When the selected edge occurs on the external
+interrupt line, an interrupt request is generated. The pending bit
+corresponding to the interrupt line is also set. This request is
+reset by writing a '1' in the pending register.
+
+Hardware interrupt selection:
+
+To configure the 20 lines as interrupt sources, use the following
+procedure:
+
+1) Configure AFIO_EXTICR[y] to select the source input for EXTIx
+ external interrupt
+2) Configure the mask bits of the 20 interrupt lines (EXTI_IMR)
+3) Configure the trigger selection bits of the interrupt lines
+ (EXTI_RTSR and EXTI_FTSR)
+4) Configure the enable and mask bits that control the NVIC_IRQ
+ channel mapped to the External Interrupt Controller (EXTI) so
+ that an inerrupt coming from one of the 20 lines can be
+ correctly acknowledged.
+
+AFIO clock must be on.
+
+RM0008, page 107: "PD0, PD1 cannot be used for external
+interrupt/event generation on 36, 48, 64-bin packages."
+
+----------------------------------------------------------------------------
+Pin to EXTI Line Mappings:
+EXTI0 EXTI1 EXTI2 EXTI3 EXTI4
+--------------------------------------------------------------------------
+D2/PA0 D3/PA1 D1/PA2 D0/A6/PA3 D10/A10/PA4
+D26/EXT7/PB0 D27/EXT8/PB1 D16/A2/PC2 D17/A3/PC3 D18/A4/PC4
+D14/A0/PC0 D15/PC1 D25/EXT5/PD2
+
+EXTI5 EXTI6 EXTI7 EXTI8 EXTI9
+----------------------------------------------------------------------------
+D13/A13/PA5 D12/A12/PA6 D11/A11/PA7 D6/PA8 D7/PA9
+D4/PB5 D5/PB6 D9/PB7 D38/PB8 D23/EXT4/PB9
+D19/A5/PC5 D34/EXTI15/PC6 D35/EXT16/PC7 D36/PC8 D37/EXT18/PC9
+
+EXTI10 EXTI11 EXTI12 EXTI13 EXTI14
+----------------------------------------------------------------------------
+D8/PA10 D29/EXT10/PB11 D30/EXTI1/PB12 D31/EXTI12/PB13 D32/EXT13/PB14
+D28/PB10 D20/EXTI1/PC13 D21/EXT2/PC14
+D25/PC10
+
+EXTI15
+----------------------------------------------------------------------------
+D33/EXTI14/PB15
+D22/EXT3/PC15
+
+
+The 16 EXTI interrupts are mapped to 7 interrupt handlers.
+
+EXTI Lines to Interrupt Mapping:
+EXTI0 -> EXTI0
+EXTI1 -> EXTI1
+EXTI2 -> EXTI2
+EXTI3 -> EXTI3
+EXTI4 -> EXTI4
+EXTI[5-9] -> EXT9_5
+EXTI[10-15] -> EXT15_10
diff --git a/wirish/HardwareTimer.cpp b/wirish/HardwareTimer.cpp
index 0f8bec6..04d1c76 100644
--- a/wirish/HardwareTimer.cpp
+++ b/wirish/HardwareTimer.cpp
@@ -89,7 +89,7 @@ uint16 HardwareTimer::setPeriod(uint32 microseconds) {
return this->getOverflow();
}
-inline void HardwareTimer::setChannelMode(int channel, TimerMode mode) {
+void HardwareTimer::setChannelMode(int channel, TimerMode mode) {
timer_set_mode(this->timerNum, channel, mode);
}
@@ -109,7 +109,7 @@ void HardwareTimer::setChannel4Mode(TimerMode mode) {
this->setChannelMode(4, mode);
}
-inline uint16 HardwareTimer::getCompare(int channel) {
+uint16 HardwareTimer::getCompare(int channel) {
return timer_get_compare_value(this->timerNum, channel);
}
@@ -129,7 +129,7 @@ uint16 HardwareTimer::getCompare4() {
return this->getCompare(4);
}
-inline void HardwareTimer::setCompare(int channel, uint16 val) {
+void HardwareTimer::setCompare(int channel, uint16 val) {
uint16 ovf = this->getOverflow();
timer_set_compare_value(this->timerNum, channel, min(val, ovf));
}
@@ -150,7 +150,7 @@ void HardwareTimer::setCompare4(uint16 val) {
this->setCompare(4, val);
}
-inline void HardwareTimer::attachInterrupt(int channel, voidFuncPtr handler) {
+void HardwareTimer::attachInterrupt(int channel, voidFuncPtr handler) {
timer_attach_interrupt(this->timerNum, channel, handler);
}
@@ -170,7 +170,7 @@ void HardwareTimer::attachCompare4Interrupt(voidFuncPtr handler) {
this->attachInterrupt(4, handler);
}
-inline void HardwareTimer::detachInterrupt(int channel) {
+void HardwareTimer::detachInterrupt(int channel) {
timer_detach_interrupt(this->timerNum, channel);
}
@@ -194,7 +194,6 @@ void HardwareTimer::generateUpdate(void) {
timer_generate_update(this->timerNum);
}
-
HardwareTimer Timer1(TIMER1);
HardwareTimer Timer2(TIMER2);
HardwareTimer Timer3(TIMER3);
diff --git a/wirish/boards.cpp b/wirish/boards.cpp
new file mode 100644
index 0000000..9276f36
--- /dev/null
+++ b/wirish/boards.cpp
@@ -0,0 +1,387 @@
+#include "boards.h"
+
+// think of the poor column numbers
+#define ADCx ADC_INVALID
+#define TIMERx TIMER_INVALID
+
+#if defined(BOARD_maple)
+
+PinMapping PIN_MAP[NR_GPIO_PINS] = {
+ /* D0/PA3 */
+ {GPIOA, 3, 3, TIMER2_CH4_CCR, TIMER2, 4, AFIO_EXTI_PA},
+ /* D1/PA2 */
+ {GPIOA, 2, 2, TIMER2_CH3_CCR, TIMER2, 3, AFIO_EXTI_PA},
+ /* D2/PA0 */
+ {GPIOA, 0, 0, TIMER2_CH1_CCR, TIMER2, 1, AFIO_EXTI_PA},
+ /* D3/PA1 */
+ {GPIOA, 1, 1, TIMER2_CH2_CCR, TIMER2, 2, AFIO_EXTI_PA},
+ /* D4/PB5 */
+ {GPIOB, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D5/PB6 */
+ {GPIOB, 6, ADCx, TIMER4_CH1_CCR, TIMER4, 1, AFIO_EXTI_PB},
+ /* D6/PA8 */
+ {GPIOA, 8, ADCx, TIMER1_CH1_CCR, TIMER1, 1, AFIO_EXTI_PA},
+ /* D7/PA9 */
+ {GPIOA, 9, ADCx, TIMER1_CH2_CCR, TIMER1, 2, AFIO_EXTI_PA},
+ /* D8/PA10 */
+ {GPIOA, 10, ADCx, TIMER1_CH3_CCR, TIMER1, 3, AFIO_EXTI_PA},
+ /* D9/PB7 */
+ {GPIOB, 7, ADCx, TIMER4_CH2_CCR, TIMER4, 2, AFIO_EXTI_PB},
+ /* D10/PA4 */
+ {GPIOA, 4, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PA},
+ /* D11/PA7 */
+ {GPIOA, 7, 7, TIMER3_CH2_CCR, TIMER3, 2, AFIO_EXTI_PA},
+ /* D12/PA6 */
+ {GPIOA, 6, 6, TIMER3_CH1_CCR, TIMER3, 1, AFIO_EXTI_PA},
+ /* D13/PA5 */
+ {GPIOA, 5, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PA},
+ /* D14/PB8 */
+ {GPIOB, 8, ADCx, TIMER4_CH3_CCR, TIMER4, 3, AFIO_EXTI_PB},
+
+ /* Little header */
+
+ /* D15/PC0 */
+ {GPIOC, 0, 10, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D16/PC1 */
+ {GPIOC, 1, 11, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D17/PC2 */
+ {GPIOC, 2, 12, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D18/PC3 */
+ {GPIOC, 3, 13, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D19/PC4 */
+ {GPIOC, 4, 14, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D20/PC5 */
+ {GPIOC, 5, 15, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+
+ /* External header */
+
+ /* D21/PC13 */
+ {GPIOC, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D22/PC14 */
+ {GPIOC, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D23/PC15 */
+ {GPIOC, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D24/PB9 */
+ {GPIOB, 9, ADCx, TIMER4_CH4_CCR, TIMER4, 4, AFIO_EXTI_PB},
+ /* D25/PD2 */
+ {GPIOD, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D26/PC10 */
+ {GPIOC, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D27/PB0 */
+ {GPIOB, 0, 8, TIMER3_CH3_CCR, TIMER3, 3, AFIO_EXTI_PB},
+ /* D28/PB1 */
+ {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB},
+ /* D29/PB10 */
+ {GPIOB, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D30/PB11 */
+ {GPIOB, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D31/PB12 */
+ {GPIOB, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D32/PB13 */
+ {GPIOB, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D33/PB14 */
+ {GPIOB, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D34/PB15 */
+ {GPIOB, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D35/PC6 */
+ {GPIOC, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D36/PC7 */
+ {GPIOC, 7, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D37/PC8 */
+ {GPIOC, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D38/PC9 (BUT) */
+ {GPIOC, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC}
+};
+
+#elif defined(BOARD_maple_native)
+
+PinMapping PIN_MAP[NR_GPIO_PINS] = {
+ /* Top header */
+
+ /* D0/PB10 */
+ {GPIOB, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D1/PB2 */
+ {GPIOB, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D2/PB12 */
+ {GPIOB, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D3/PB13 */
+ {GPIOB, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D4/PB14 */
+ {GPIOB, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D5/PB15 */
+ {GPIOB, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D6/PC0 */
+ {GPIOC, 0, 10, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D7/PC1 */
+ {GPIOC, 1, 11, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D8/PC2 */
+ {GPIOC, 2, 12, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D9/PC3 */
+ {GPIOC, 3, 13, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D10/PC4 */
+ {GPIOC, 4, 14, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D11/PC5 */
+ {GPIOC, 5, 15, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D12/PC6 */
+ {GPIOC, 6, ADCx, TIMER8_CH1_CCR, TIMER8, 1, AFIO_EXTI_PC},
+ /* D13/PC7 */
+ {GPIOC, 7, ADCx, TIMER8_CH2_CCR, TIMER8, 2, AFIO_EXTI_PC},
+ /* D14/PC8 */
+ {GPIOC, 8, ADCx, TIMER8_CH3_CCR, TIMER8, 3, AFIO_EXTI_PC},
+ /* D15/PC9 */
+ {GPIOC, 9, ADCx, TIMER8_CH4_CCR, TIMER8, 4, AFIO_EXTI_PC},
+ /* D16/PC10 */
+ {GPIOC, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D17/PC11 */
+ {GPIOC, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D18/PC12 */
+ {GPIOC, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D19/PC13 */
+ {GPIOC, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D20/PC14 */
+ {GPIOC, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D21/PC15 */
+ {GPIOC, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D22/PA8 */
+ {GPIOA, 8, ADCx, TIMER1_CH1_CCR, TIMER1, 1, AFIO_EXTI_PA},
+ /* D23/PA9 */
+ {GPIOA, 9, ADCx, TIMER1_CH2_CCR, TIMER1, 2, AFIO_EXTI_PA},
+ /* D24/PA10 */
+ {GPIOA, 10, ADCx, TIMER1_CH3_CCR, TIMER1, 3, AFIO_EXTI_PA},
+ /* D25/PB9 */
+ {GPIOB, 9, ADCx, TIMER4_CH4_CCR, TIMER4, 4, AFIO_EXTI_PB},
+
+ /* Bottom header */
+
+ /* D26/PD2 */
+ {GPIOD, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D27/PD3 */
+ {GPIOD, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D28/PD6 */
+ {GPIOD, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D29/PG11 */
+ {GPIOG, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D30/PG12 */
+ {GPIOG, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D31/PG13 */
+ {GPIOG, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D32/PG14 */
+ {GPIOG, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D33/PG8 */
+ {GPIOG, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D34/PG7 */
+ {GPIOG, 7, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D35/PG6 */
+ {GPIOG, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D36/PB5 */
+ {GPIOB, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D37/PB6 */
+ {GPIOB, 6, ADCx, TIMER4_CH1_CCR, TIMER4, 1, AFIO_EXTI_PB},
+ /* D38/PB7 */
+ {GPIOB, 7, ADCx, TIMER4_CH2_CCR, TIMER4, 2, AFIO_EXTI_PB},
+ /* D39/PF6 */
+ {GPIOF, 6, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D40/PF7 */
+ {GPIOF, 7, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D41/PF8 */
+ {GPIOF, 8, 6, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D42/PF9 */
+ {GPIOF, 9, 7, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D43/PF10 */
+ {GPIOF, 10, 8, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D44/PF11 */
+ {GPIOF, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D45/PB1 */
+ {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB},
+ /* D46/PB0 */
+ {GPIOB, 0, 8, TIMER3_CH3_CCR, TIMER3, 3, AFIO_EXTI_PB},
+ /* D47/PA0 */
+ {GPIOA, 0, 0, TIMER5_CH1_CCR, TIMER5, 1, AFIO_EXTI_PA},
+ /* D48/PA1 */ /* FIXME (?)
+ What about D48--D50 also being TIMER2_CH[234]? */
+ {GPIOA, 1, 1, TIMER5_CH2_CCR, TIMER5, 2, AFIO_EXTI_PA},
+ /* D49/PA2 */
+ {GPIOA, 2, 2, TIMER5_CH3_CCR, TIMER5, 3, AFIO_EXTI_PA},
+ /* D50/PA3 */
+ {GPIOA, 3, 3, TIMER5_CH4_CCR, TIMER5, 4, AFIO_EXTI_PA},
+ /* D51/PA4 */
+ {GPIOA, 4, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PA},
+ /* D52/PA5 */
+ {GPIOA, 5, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PA},
+ /* D53/PA6 */
+ {GPIOA, 6, 6, TIMER3_CH1_CCR, TIMER3, 1, AFIO_EXTI_PA},
+ /* D54/PA7 */
+ {GPIOA, 7, 7, TIMER3_CH2_CCR, TIMER3, 2, AFIO_EXTI_PA},
+
+ /* Right (triple) header */
+
+ /* D55/PF0 */
+ {GPIOF, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D56/PD11 */
+ {GPIOD, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D57/PD14 */
+ {GPIOD, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D58/PF1 */
+ {GPIOF, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D59/PD12 */
+ {GPIOD, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D60/PD15 */
+ {GPIOD, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D61/PF2 */
+ {GPIOF, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D62/PD13 */
+ {GPIOD, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D63/PD0 */
+ {GPIOD, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D64/PF3 */
+ {GPIOF, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D65/PE3 */
+ {GPIOE, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D66/PD1 */
+ {GPIOD, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D67/PF4 */
+ {GPIOF, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D68/PE4 */
+ {GPIOE, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D69/PE7 */
+ {GPIOE, 7, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D70/PF5 */
+ {GPIOF, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D71/PE5 */
+ {GPIOE, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D72/PE8 */
+ {GPIOE, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D73/PF12 */
+ {GPIOF, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D74/PE6 */
+ {GPIOE, 6, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D75/PE9 */
+ {GPIOE, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D76/PF13 */
+ {GPIOF, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D77/PE10 */
+ {GPIOE, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D78/PF14 */
+ {GPIOF, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D79/PG9 */
+ {GPIOG, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D80/PE11 */
+ {GPIOE, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D81/PF15 */
+ {GPIOF, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PF},
+ /* D82/PG10 */
+ {GPIOG, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D83/PE12 */
+ {GPIOE, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D84/PG0 */
+ {GPIOG, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D85/PD5 */
+ {GPIOD, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D86/PE13 */
+ {GPIOE, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D87/PG1 */
+ {GPIOG, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D88/PD4 */
+ {GPIOD, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D89/PE14 */
+ {GPIOE, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D90/PG2 */
+ {GPIOG, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D91/PE1 */
+ {GPIOE, 1, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D92/PE15 */
+ {GPIOE, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D93/PG3 */
+ {GPIOG, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D94/PE0 */
+ {GPIOE, 0, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PE},
+ /* D95/PD8 */
+ {GPIOD, 8, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D96/PG4 */
+ {GPIOG, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D97/PD9 */
+ {GPIOD, 9, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PD},
+ /* D98/PG5 */
+ {GPIOG, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PG},
+ /* D99/PD10 */
+ {GPIOD, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PDD}
+};
+
+#elif defined(BOARD_maple_mini)
+
+PinMapping PIN_MAP[NR_GPIO_PINS] = {
+ /* D0/PB11 */
+ {GPIOB, 11, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D1/PB10 */
+ {GPIOB, 10, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D2/PB2 */
+ {GPIOB, 2, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D3/PB0 */
+ {GPIOB, 0, 8, TIMER3_CH3_CCR, TIMER3, 3, AFIO_EXTI_PB},
+ /* D4/PA7 */
+ {GPIOA, 7, 7, TIMER3_CH2_CCR, TIMER3, 2, AFIO_EXTI_PA},
+ /* D5/PA6 */
+ {GPIOA, 6, 6, TIMER3_CH1_CCR, TIMER3, 1, AFIO_EXTI_PA},
+ /* D6/PA5 */
+ {GPIOA, 5, 5, 0, TIMERx, TIMERx, AFIO_EXTI_PA},
+ /* D7/PA4 */
+ {GPIOA, 4, 4, 0, TIMERx, TIMERx, AFIO_EXTI_PA},
+ /* D8/PA3 */
+ {GPIOA, 3, 3, TIMER2_CH4_CCR, TIMER2, 4, AFIO_EXTI_PA},
+ /* D9/PA2 */
+ {GPIOA, 2, 2, TIMER2_CH3_CCR, TIMER2, 3, AFIO_EXTI_PA},
+ /* D10/PA1 */
+ {GPIOA, 1, 1, TIMER2_CH2_CCR, TIMER2, 2, AFIO_EXTI_PA},
+ /* D11/PA0 */
+ {GPIOA, 0, 0, TIMER2_CH1_CCR, TIMER2, 1, AFIO_EXTI_PA},
+ /* D12/PC15 */
+ {GPIOC, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D13/PC14 */
+ {GPIOC, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D14/PC13 */
+ {GPIOC, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PC},
+ /* D15/PB7 */
+ {GPIOB, 7, ADCx, TIMER4_CH2_CCR, TIMER4, 2, AFIO_EXTI_PB},
+ /* D16/PB6 */
+ {GPIOB, 6, ADCx, TIMER4_CH1_CCR, TIMER4, 1, AFIO_EXTI_PB},
+ /* D17/PB5 */
+ {GPIOB, 5, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D18/PB4 */
+ {GPIOB, 4, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D19/PB3 */
+ {GPIOB, 3, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D20/PA15 */
+ {GPIOA, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA},
+ /* D21/PA14 */
+ {GPIOA, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA},
+ /* D22/PA13 */
+ {GPIOA, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA},
+ /* D23/PA12 */
+ {GPIOA, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PA},
+ /* D24/PA11 */
+ {GPIOA, 11, ADCx, TIMER1_CH4_CCR, TIMER1, 4, AFIO_EXTI_PA},
+ /* D25/PA10 */
+ {GPIOA, 10, ADCx, TIMER1_CH3_CCR, TIMER1, 3, AFIO_EXTI_PA},
+ /* D26/PA9 */
+ {GPIOA, 9, ADCx, TIMER1_CH2_CCR, TIMER2, 2, AFIO_EXTI_PA},
+ /* D27/PA8 */
+ {GPIOA, 8, ADCx, TIMER1_CH1_CCR, TIMER1, 1, AFIO_EXTI_PA},
+ /* D28/PB15 */
+ {GPIOB, 15, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D29/PB14 */
+ {GPIOB, 14, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D30/PB13 */
+ {GPIOB, 13, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D31/PB12 */
+ {GPIOB, 12, ADCx, 0, TIMERx, TIMERx, AFIO_EXTI_PB},
+ /* D32/PB8 */
+ {GPIOB, 8, ADCx, TIMER4_CH3_CCR, TIMER4, 3, AFIO_EXTI_PB},
+ /* D33/PB1 */
+ {GPIOB, 1, 9, TIMER3_CH4_CCR, TIMER3, 4, AFIO_EXTI_PB},
+};
+
+#else
+
+#error "Board type has not been selected correctly."
+
+#endif
diff --git a/wirish/boards.h b/wirish/boards.h
index ee93c5a..2941127 100644
--- a/wirish/boards.h
+++ b/wirish/boards.h
@@ -34,13 +34,11 @@
#include "libmaple.h"
#include "gpio.h"
#include "timers.h"
-#include "exti.h"
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/* Set of all possible digital pin names; not all boards have all these */
+/* Set of all possible pin names; not all boards have all these (note
+ that we use the Dx convention since all of the Maple's pins are
+ "digital" pins (e.g. can be used with digitalRead() and
+ digitalWrite()), but not all of them are connected to ADCs. */
enum {
D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, D10, D11, D12, D13, D14, D15, D16,
D17, D18, D19, D20, D21, D22, D23, D24, D25, D26, D27, D28, D29, D30, D31,
@@ -53,17 +51,20 @@ enum {
#define ADC_INVALID 0xFFFFFFFF
-/* Types used for the tables below */
+/* Pin mapping: pin number -> STM32 info */
typedef struct PinMapping {
- GPIO_Port *port;
+ gpio_dev *gpio_device;
uint32 pin;
uint32 adc_channel;
TimerCCR timer_ccr;
- uint32 exti_port;
timer_dev_num timer_num;
uint32 timer_chan;
+ afio_exti_port ext_port;
} PinMapping;
+/* Maps every digital pin to a PinMapping */
+extern PinMapping PIN_MAP[];
+
/* LeafLabs Maple rev3, rev5 */
#ifdef BOARD_maple
@@ -77,93 +78,6 @@ typedef struct PinMapping {
intended for general use. */
#define NR_GPIO_PINS 39
- static __attribute__ ((unused)) PinMapping PIN_MAP[NR_GPIO_PINS] = {
- /* D0/PA3 */
- {GPIOA_BASE, 3, 3, TIMER2_CH4_CCR, EXTI_CONFIG_PORTA, TIMER2, 4},
- /* D1/PA2 */
- {GPIOA_BASE, 2, 2, TIMER2_CH3_CCR, EXTI_CONFIG_PORTA, TIMER2, 3},
- /* D2/PA0 */
- {GPIOA_BASE, 0, 0, TIMER2_CH1_CCR, EXTI_CONFIG_PORTA, TIMER2, 1},
- /* D3/PA1 */
- {GPIOA_BASE, 1, 1, TIMER2_CH2_CCR, EXTI_CONFIG_PORTA, TIMER2, 2},
- /* D4/PB5 */
- {GPIOB_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D5/PB6 */
- {GPIOB_BASE, 6, ADC_INVALID, TIMER4_CH1_CCR, EXTI_CONFIG_PORTB, TIMER4, 1},
- /* D6/PA8 */
- {GPIOA_BASE, 8, ADC_INVALID, TIMER1_CH1_CCR, EXTI_CONFIG_PORTA, TIMER1, 1},
- /* D7/PA9 */
- {GPIOA_BASE, 9, ADC_INVALID, TIMER1_CH2_CCR, EXTI_CONFIG_PORTA, TIMER1, 2},
- /* D8/PA10 */
- {GPIOA_BASE, 10, ADC_INVALID, TIMER1_CH3_CCR, EXTI_CONFIG_PORTA, TIMER1, 3},
- /* D9/PB7 */
- {GPIOB_BASE, 7, ADC_INVALID, TIMER4_CH2_CCR, EXTI_CONFIG_PORTB, TIMER4, 2},
- /* D10/PA4 */
- {GPIOA_BASE, 4, 4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID},
- /* D11/PA7 */
- {GPIOA_BASE, 7, 7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2},
- /* D12/PA6 */
- {GPIOA_BASE, 6, 6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1},
- /* D13/PA5 */
- {GPIOA_BASE, 5, 5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID},
- /* D14/PB8 */
- {GPIOB_BASE, 8, ADC_INVALID, TIMER4_CH3_CCR, EXTI_CONFIG_PORTB, TIMER4, 3},
-
- /* Little header */
-
- /* D15/PC0 */
- {GPIOC_BASE, 0, 10, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D16/PC1 */
- {GPIOC_BASE, 1, 11, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D17/PC2 */
- {GPIOC_BASE, 2, 12, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D18/PC3 */
- {GPIOC_BASE, 3, 13, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D19/PC4 */
- {GPIOC_BASE, 4, 14, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D20/PC5 */
- {GPIOC_BASE, 5, 15, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
-
- /* External header */
-
- /* D21/PC13 */
- {GPIOC_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D22/PC14 */
- {GPIOC_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D23/PC15 */
- {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D24/PB9 */
- {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER4, 4},
- /* D25/PD2 */
- {GPIOD_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D26/PC10 */
- {GPIOC_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D27/PB0 */
- {GPIOB_BASE, 0, 8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3},
- /* D28/PB1 */
- {GPIOB_BASE, 1, 9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4},
- /* D29/PB10 */
- {GPIOB_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D30/PB11 */
- {GPIOB_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D31/PB12 */
- {GPIOB_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D32/PB13 */
- {GPIOB_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D33/PB14 */
- {GPIOB_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D34/PB15 */
- {GPIOB_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D35/PC6 */
- {GPIOC_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D36/PC7 */
- {GPIOC_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D37/PC8 */
- {GPIOC_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D38/PC9 (BUT) */
- {GPIOC_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID}
- };
-
#define BOARD_INIT do { \
} while(0)
@@ -179,218 +93,6 @@ typedef struct PinMapping {
#define NR_GPIO_PINS 100
- static __attribute__ ((unused)) PinMapping PIN_MAP[NR_GPIO_PINS] = {
- /* Top header */
-
- /* D0/PB10 */
- {GPIOB_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D1/PB2 */
- {GPIOB_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D2/PB12 */
- {GPIOB_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D3/PB13 */
- {GPIOB_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D4/PB14 */
- {GPIOB_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D5/PB15 */
- {GPIOB_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D6/PC0 */
- {GPIOC_BASE, 0, 10, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D7/PC1 */
- {GPIOC_BASE, 1, 11, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D8/PC2 */
- {GPIOC_BASE, 2, 12, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D9/PC3 */
- {GPIOC_BASE, 3, 13, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D10/PC4 */
- {GPIOC_BASE, 4, 14, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D11/PC5 */
- {GPIOC_BASE, 5, 15, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D12/PC6 */
- {GPIOC_BASE, 6, ADC_INVALID, TIMER8_CH1_CCR, EXTI_CONFIG_PORTC, TIMER8, 1},
- /* D13/PC7 */
- {GPIOC_BASE, 7, ADC_INVALID, TIMER8_CH2_CCR, EXTI_CONFIG_PORTC, TIMER8, 2},
- /* D14/PC8 */
- {GPIOC_BASE, 8, ADC_INVALID, TIMER8_CH3_CCR, EXTI_CONFIG_PORTC, TIMER8, 3},
- /* D15/PC9 */
- {GPIOC_BASE, 9, ADC_INVALID, TIMER8_CH4_CCR, EXTI_CONFIG_PORTC, TIMER8, 4},
- /* D16/PC10 */
- {GPIOC_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D17/PC11 */
- {GPIOC_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D18/PC12 */
- {GPIOC_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D19/PC13 */
- {GPIOC_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D20/PC14 */
- {GPIOC_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D21/PC15 */
- {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D22/PA8 */
- {GPIOA_BASE, 8, ADC_INVALID, TIMER1_CH1_CCR, EXTI_CONFIG_PORTA, TIMER1, 1},
- /* D23/PA9 */
- {GPIOA_BASE, 9, ADC_INVALID, TIMER1_CH2_CCR, EXTI_CONFIG_PORTA, TIMER1, 2},
- /* D24/PA10 */
- {GPIOA_BASE, 10, ADC_INVALID, TIMER1_CH3_CCR, EXTI_CONFIG_PORTA, TIMER1, 3},
- /* D25/PB9 */
- {GPIOB_BASE, 9, ADC_INVALID, TIMER4_CH4_CCR, EXTI_CONFIG_PORTB, TIMER4, 4},
-
- /* Bottom header */
-
- /* D26/PD2 */
- {GPIOD_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D27/PD3 */
- {GPIOD_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D28/PD6 */
- {GPIOD_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D29/PG11 */
- {GPIOG_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D30/PG12 */
- {GPIOG_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D31/PG13 */
- {GPIOG_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D32/PG14 */
- {GPIOG_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D33/PG8 */
- {GPIOG_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D34/PG7 */
- {GPIOG_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D35/PG6 */
- {GPIOG_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D36/PB5 */
- {GPIOB_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D37/PB6 */
- {GPIOB_BASE, 6, ADC_INVALID, TIMER4_CH1_CCR, EXTI_CONFIG_PORTB, TIMER4, 1},
- /* D38/PB7 */
- {GPIOB_BASE, 7, ADC_INVALID, TIMER4_CH2_CCR, EXTI_CONFIG_PORTB, TIMER4, 2},
- /* D39/PF6 */
- {GPIOF_BASE, 6, 4, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D40/PF7 */
- {GPIOF_BASE, 7, 5, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D41/PF8 */
- {GPIOF_BASE, 8, 6, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D42/PF9 */
- {GPIOF_BASE, 9, 7, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D43/PF10 */
- {GPIOF_BASE, 10, 8, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D44/PF11 */
- {GPIOF_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D45/PB1 */
- {GPIOB_BASE, 1, 9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4},
- /* D46/PB0 */
- {GPIOB_BASE, 0, 8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3},
- /* D47/PA0 */
- {GPIOA_BASE, 0, 0, TIMER5_CH1_CCR, EXTI_CONFIG_PORTA, TIMER5, 1},
- /* D48/PA1 */
- {GPIOA_BASE, 1, 1, TIMER5_CH2_CCR, EXTI_CONFIG_PORTA, TIMER5, 2}, /* FIXME (?) what to do about D48--D50
- also being TIMER2_CH[2,3,4]? */
- /* D49/PA2 */
- {GPIOA_BASE, 2, 2, TIMER5_CH3_CCR, EXTI_CONFIG_PORTA, TIMER5, 3},
- /* D50/PA3 */
- {GPIOA_BASE, 3, 3, TIMER5_CH4_CCR, EXTI_CONFIG_PORTA, TIMER5, 4},
- /* D51/PA4 */
- {GPIOA_BASE, 4, 4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID},
- /* D52/PA5 */
- {GPIOA_BASE, 5, 5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID},
- /* D53/PA6 */
- {GPIOA_BASE, 6, 6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1},
- /* D54/PA7 */
- {GPIOA_BASE, 7, 7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2},
-
- /* Right (triple) header */
-
- /* D55/PF0 */
- {GPIOF_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D56/PD11 */
- {GPIOD_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D57/PD14 */
- {GPIOD_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D58/PF1 */
- {GPIOF_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D59/PD12 */
- {GPIOD_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D60/PD15 */
- {GPIOD_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D61/PF2 */
- {GPIOF_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D62/PD13 */
- {GPIOD_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D63/PD0 */
- {GPIOD_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D64/PF3 */
- {GPIOF_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D65/PE3 */
- {GPIOE_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D66/PD1 */
- {GPIOD_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D67/PF4 */
- {GPIOF_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D68/PE4 */
- {GPIOE_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D69/PE7 */
- {GPIOE_BASE, 7, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D70/PF5 */
- {GPIOF_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D71/PE5 */
- {GPIOE_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D72/PE8 */
- {GPIOE_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D73/PF12 */
- {GPIOF_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D74/PE6 */
- {GPIOE_BASE, 6, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D75/PE9 */
- {GPIOE_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D76/PF13 */
- {GPIOF_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D77/PE10 */
- {GPIOE_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D78/PF14 */
- {GPIOF_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D79/PG9 */
- {GPIOG_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D80/PE11 */
- {GPIOE_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D81/PF15 */
- {GPIOF_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTF, TIMER_INVALID, TIMER_INVALID},
- /* D82/PG10 */
- {GPIOG_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D83/PE12 */
- {GPIOE_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D84/PG0 */
- {GPIOG_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D85/PD5 */
- {GPIOD_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D86/PE13 */
- {GPIOE_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D87/PG1 */
- {GPIOG_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D88/PD4 */
- {GPIOD_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D89/PE14 */
- {GPIOE_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D90/PG2 */
- {GPIOG_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D91/PE1 */
- {GPIOE_BASE, 1, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D92/PE15 */
- {GPIOE_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D93/PG3 */
- {GPIOG_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D94/PE0 */
- {GPIOE_BASE, 0, ADC_INVALID, 0, EXTI_CONFIG_PORTE, TIMER_INVALID, TIMER_INVALID},
- /* D95/PD8 */
- {GPIOD_BASE, 8, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D96/PG4 */
- {GPIOG_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D97/PD9 */
- {GPIOD_BASE, 9, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID},
- /* D98/PG5 */
- {GPIOG_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTG, TIMER_INVALID, TIMER_INVALID},
- /* D99/PD10 */
- {GPIOD_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTD, TIMER_INVALID, TIMER_INVALID}
- };
-
#define BOARD_INIT do { \
} while(0)
@@ -404,83 +106,11 @@ typedef struct PinMapping {
#define NR_GPIO_PINS 34
- static __attribute__ ((unused)) PinMapping PIN_MAP[NR_GPIO_PINS] = {
- /* D0/PB11 */
- {GPIOB_BASE, 11, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D1/PB10 */
- {GPIOB_BASE, 10, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D2/PB2 */
- {GPIOB_BASE, 2, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D3/PB0 */
- {GPIOB_BASE, 0, 8, TIMER3_CH3_CCR, EXTI_CONFIG_PORTB, TIMER3, 3},
- /* D4/PA7 */
- {GPIOA_BASE, 7, 7, TIMER3_CH2_CCR, EXTI_CONFIG_PORTA, TIMER3, 2},
- /* D5/PA6 */
- {GPIOA_BASE, 6, 6, TIMER3_CH1_CCR, EXTI_CONFIG_PORTA, TIMER3, 1},
- /* D6/PA5 */
- {GPIOA_BASE, 5, 5, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID},
- /* D7/PA4 */
- {GPIOA_BASE, 4, 4, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID},
- /* D8/PA3 */
- {GPIOA_BASE, 3, 3, TIMER2_CH4_CCR, EXTI_CONFIG_PORTA, TIMER2, 4},
- /* D9/PA2 */
- {GPIOA_BASE, 2, 2, TIMER2_CH3_CCR, EXTI_CONFIG_PORTA, TIMER2, 3},
- /* D10/PA1 */
- {GPIOA_BASE, 1, 1, TIMER2_CH2_CCR, EXTI_CONFIG_PORTA, TIMER2, 2},
- /* D11/PA0 */
- {GPIOA_BASE, 0, 0, TIMER2_CH1_CCR, EXTI_CONFIG_PORTA, TIMER2, 1},
- /* D12/PC15 */
- {GPIOC_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D13/PC14 */
- {GPIOC_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D14/PC13 */
- {GPIOC_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTC, TIMER_INVALID, TIMER_INVALID},
- /* D15/PB7 */
- {GPIOB_BASE, 7, ADC_INVALID, TIMER4_CH2_CCR, EXTI_CONFIG_PORTB, TIMER4, 1},
- /* D16/PB6 */
- {GPIOB_BASE, 6, ADC_INVALID, TIMER4_CH1_CCR, EXTI_CONFIG_PORTB, TIMER4, 1},
- /* D17/PB5 */
- {GPIOB_BASE, 5, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D18/PB4 */
- {GPIOB_BASE, 4, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D19/PB3 */
- {GPIOB_BASE, 3, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D20/PA15 */
- {GPIOA_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID},
- /* D21/PA14 */
- {GPIOA_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID},
- /* D22/PA13 */
- {GPIOA_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID},
- /* D23/PA12 */
- {GPIOA_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTA, TIMER_INVALID, TIMER_INVALID},
- /* D24/PA11 */
- {GPIOA_BASE, 11, ADC_INVALID, TIMER1_CH4_CCR, EXTI_CONFIG_PORTA, TIMER1, 4},
- /* D25/PA10 */
- {GPIOA_BASE, 10, ADC_INVALID, TIMER1_CH3_CCR, EXTI_CONFIG_PORTA, TIMER1, 3},
- /* D26/PA9 */
- {GPIOA_BASE, 9, ADC_INVALID, TIMER1_CH2_CCR, EXTI_CONFIG_PORTA, TIMER2, 2},
- /* D27/PA8 */
- {GPIOA_BASE, 8, ADC_INVALID, TIMER1_CH1_CCR, EXTI_CONFIG_PORTB, TIMER1, 1},
- /* D28/PB15 */
- {GPIOB_BASE, 15, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D29/PB14 */
- {GPIOB_BASE, 14, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D30/PB13 */
- {GPIOB_BASE, 13, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D31/PB12 */
- {GPIOB_BASE, 12, ADC_INVALID, 0, EXTI_CONFIG_PORTB, TIMER_INVALID, TIMER_INVALID},
- /* D32/PB8 */
- {GPIOB_BASE, 8, ADC_INVALID, TIMER4_CH3_CCR, EXTI_CONFIG_PORTB, TIMER4, 3},
- /* D33/PB1 */
- {GPIOB_BASE, 1, 9, TIMER3_CH4_CCR, EXTI_CONFIG_PORTB, TIMER3, 4},
- };
-
- /* since we want the Serial Wire/JTAG pins as GPIOs, disable both
- SW and JTAG debug support */
- /* don't use __clear_bits here! */
+ /* Since we want the Serial Wire/JTAG pins as GPIOs, disable both
+ * SW and JTAG debug support */
#define BOARD_INIT \
do { \
- *AFIO_MAPR = (*AFIO_MAPR | BIT(26)) & ~(BIT(25) | BIT(24)); \
+ afio_mapr_swj_config(AFIO_MAPR_SWJ_NO_JTAG_NO_SW); \
} while (0)
#else
@@ -489,9 +119,4 @@ typedef struct PinMapping {
#endif
-#ifdef __cplusplus
-} // extern "C"
-#endif
-
#endif
-
diff --git a/wirish/comm/HardwareSerial.cpp b/wirish/comm/HardwareSerial.cpp
index d6c7e82..08252d8 100644
--- a/wirish/comm/HardwareSerial.cpp
+++ b/wirish/comm/HardwareSerial.cpp
@@ -34,21 +34,21 @@
#include "gpio.h"
#include "timers.h"
-HardwareSerial Serial1(USART1, 4500000UL, GPIOA_BASE, 9,10, TIMER1, 2);
-HardwareSerial Serial2(USART2, 2250000UL, GPIOA_BASE, 2, 3, TIMER2, 3);
-HardwareSerial Serial3(USART3, 2250000UL, GPIOB_BASE, 10,11, TIMER_INVALID, 0);
+HardwareSerial Serial1(USART1, 4500000UL, GPIOA, 9,10, TIMER1, 2);
+HardwareSerial Serial2(USART2, 2250000UL, GPIOA, 2, 3, TIMER2, 3);
+HardwareSerial Serial3(USART3, 2250000UL, GPIOB, 10,11, TIMER_INVALID, 0);
// TODO: High density device ports
HardwareSerial::HardwareSerial(uint8 usart_num,
uint32 max_baud,
- GPIO_Port *gpio_port,
+ gpio_dev *gpio_device,
uint8 tx_pin,
uint8 rx_pin,
timer_dev_num timer_num,
uint8 compare_num) {
this->usart_num = usart_num;
this->max_baud = max_baud;
- this->gpio_port = gpio_port;
+ this->gpio_device = gpio_device;
this->tx_pin = tx_pin;
this->rx_pin = rx_pin;
this->timer_num = timer_num;
@@ -72,8 +72,8 @@ void HardwareSerial::begin(uint32 baud) {
return;
}
- gpio_set_mode(gpio_port, tx_pin, GPIO_MODE_AF_OUTPUT_PP);
- gpio_set_mode(gpio_port, rx_pin, GPIO_MODE_INPUT_FLOATING);
+ gpio_set_mode(gpio_device, tx_pin, GPIO_AF_OUTPUT_PP);
+ gpio_set_mode(gpio_device, rx_pin, GPIO_INPUT_FLOATING);
if (timer_num != TIMER_INVALID) {
/* turn off any pwm if there's a conflict on this usart */
diff --git a/wirish/comm/HardwareSerial.h b/wirish/comm/HardwareSerial.h
index aad8aa7..ef19a56 100644
--- a/wirish/comm/HardwareSerial.h
+++ b/wirish/comm/HardwareSerial.h
@@ -46,7 +46,7 @@ class HardwareSerial : public Print {
private:
uint8 usart_num;
uint32 max_baud;
- GPIO_Port *gpio_port;
+ gpio_dev *gpio_device;
uint8 tx_pin;
uint8 rx_pin;
timer_dev_num timer_num;
@@ -54,7 +54,7 @@ class HardwareSerial : public Print {
public:
HardwareSerial(uint8 usart_num,
uint32 max_baud,
- GPIO_Port *gpio_port,
+ gpio_dev *gpio_device,
uint8 tx_pin,
uint8 rx_pin,
timer_dev_num timer_num,
diff --git a/wirish/ext_interrupts.c b/wirish/ext_interrupts.cpp
index dd7c1a8..5b32b05 100644
--- a/wirish/ext_interrupts.c
+++ b/wirish/ext_interrupts.cpp
@@ -28,52 +28,55 @@
* @brief Wiring-like interface for external interrupts
*/
-#include "wirish.h"
+#include "boards.h"
+#include "gpio.h"
#include "exti.h"
#include "ext_interrupts.h"
-/* Attach ISR handler on pin, triggering on the given mode. */
-void attachInterrupt(uint8 pin, voidFuncPtr handler, ExtIntTriggerMode mode) {
- uint8 outMode;
-
- /* Parameter checking */
- if (pin >= NR_GPIO_PINS) {
- return;
- }
+static inline exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode);
- if (!handler) {
+/**
+ * @brief Attach an interrupt handler to a pin, triggering on the given mode.
+ * @param pin Pin to attach an interrupt handler onto.
+ * @param handler Function to call when the external interrupt is triggered.
+ * @param mode Trigger mode for the given interrupt.
+ * @see ExtIntTriggerMode
+ */
+void attachInterrupt(uint8 pin, voidFuncPtr handler, ExtIntTriggerMode mode) {
+ if (pin >= NR_GPIO_PINS || !handler) {
return;
}
- switch (mode) {
- case RISING:
- outMode = EXTI_RISING;
- break;
- case FALLING:
- outMode = EXTI_FALLING;
- break;
- case CHANGE:
- outMode = EXTI_RISING_FALLING;
- break;
- default:
- ASSERT(0);
- return;
- }
+ exti_trigger_mode outMode = exti_out_mode(mode);
- exti_attach_interrupt(PIN_MAP[pin].exti_port,
- PIN_MAP[pin].pin,
+ exti_attach_interrupt((afio_exti_num)(PIN_MAP[pin].pin),
+ PIN_MAP[pin].ext_port,
handler,
- mode);
-
- return;
+ outMode);
}
-/* Disable any interrupts */
+/**
+ * @brief Disable any external interrupt attached to a pin.
+ * @param pin Pin number to detach any interrupt from.
+ */
void detachInterrupt(uint8 pin) {
- if (!(pin < NR_GPIO_PINS)) {
+ if (pin >= NR_GPIO_PINS) {
return;
}
- exti_detach_interrupt(PIN_MAP[pin].pin);
+ exti_detach_interrupt((afio_exti_num)(PIN_MAP[pin].pin));
}
+static inline exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode) {
+ switch (mode) {
+ case RISING:
+ return EXTI_RISING;
+ case FALLING:
+ return EXTI_FALLING;
+ case CHANGE:
+ return EXTI_RISING_FALLING;
+ }
+ // Can't happen
+ ASSERT(0);
+ return (exti_trigger_mode)0;
+}
diff --git a/wirish/ext_interrupts.h b/wirish/ext_interrupts.h
index 4e22c71..364bcda 100644
--- a/wirish/ext_interrupts.h
+++ b/wirish/ext_interrupts.h
@@ -28,7 +28,7 @@
/**
* @file ext_interrupts.h
*
- * @brief External interrupt wiring prototypes and types
+ * @brief Wiring-like external interrupt prototypes and types.
*/
#ifndef _EXT_INTERRUPTS_H_
@@ -48,10 +48,6 @@ typedef enum ExtIntTriggerMode_ {
changes). */
} ExtIntTriggerMode;
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/**
* @brief Registers an interrupt handler on a pin.
*
@@ -104,10 +100,5 @@ static inline void noInterrupts() {
nvic_globalirq_disable();
}
-#ifdef __cplusplus
-}
-#endif
-
-
#endif
diff --git a/wirish/io.h b/wirish/io.h
index 2d22dcd..d2e4d2d 100644
--- a/wirish/io.h
+++ b/wirish/io.h
@@ -35,10 +35,6 @@
#include "adc.h"
#include "time.h"
-#ifdef __cplusplus
-extern "C"{
-#endif
-
/**
* Specifies a GPIO pin behavior.
*
@@ -68,11 +64,11 @@ typedef enum WiringPinMode {
supply through a large resistor). When the
pin is high, not much current flows through
to ground and the line stays at positive
- voltage; when the pin is low the bus
+ voltage; when the pin is low, the bus
"drains" to ground with a small amount of
current constantly flowing through the large
resistor from the external supply. In this
- mode no current is ever actually /sourced/
+ mode, no current is ever actually sourced
from the pin. */
INPUT, /**< Basic digital input. The pin voltage is sampled; when
@@ -220,8 +216,5 @@ uint8 isButtonPressed();
*/
uint8 waitForButtonPress(uint32 timeout_millis);
-#ifdef __cplusplus
-} // extern "C"
-#endif
#endif
diff --git a/wirish/pwm.c b/wirish/pwm.cpp
index 072e4cd..072e4cd 100644
--- a/wirish/pwm.c
+++ b/wirish/pwm.cpp
diff --git a/wirish/pwm.h b/wirish/pwm.h
index d0bc9e0..a6385e9 100644
--- a/wirish/pwm.h
+++ b/wirish/pwm.h
@@ -28,12 +28,8 @@
* @brief Arduino-compatible PWM interface.
*/
-#ifndef _PWM_H
-#define _PWM_H
-
-#ifdef __cplusplus
-extern "C"{
-#endif
+#ifndef _PWM_H_
+#define _PWM_H_
/**
* As a convenience, analogWrite is an alias of pwmWrite to ease
@@ -50,10 +46,5 @@ extern "C"{
*/
void pwmWrite(uint8 pin, uint16 duty_cycle);
-#ifdef __cplusplus
-}
-#endif
-
-
#endif
diff --git a/wirish/rules.mk b/wirish/rules.mk
index cb5a69f..cea34f5 100644
--- a/wirish/rules.mk
+++ b/wirish/rules.mk
@@ -11,21 +11,23 @@ WIRISH_INCLUDES := -I$(d) -I$(d)/comm
CFLAGS_$(d) := $(WIRISH_INCLUDES) $(LIBMAPLE_INCLUDES)
# Local rules and targets
-cSRCS_$(d) := wirish.c \
- wirish_shift.c \
- wirish_analog.c \
- time.c \
- pwm.c \
- ext_interrupts.c \
- wirish_digital.c
-
-cppSRCS_$(d) := wirish_math.cpp \
- Print.cpp \
- comm/HardwareSerial.cpp \
- comm/HardwareSPI.cpp \
- usb_serial.cpp \
- HardwareTimer.cpp \
- cxxabi-compat.cpp \
+cSRCS_$(d) :=
+
+cppSRCS_$(d) := wirish_math.cpp \
+ Print.cpp \
+ comm/HardwareSerial.cpp \
+ comm/HardwareSPI.cpp \
+ usb_serial.cpp \
+ HardwareTimer.cpp \
+ cxxabi-compat.cpp \
+ wirish.cpp \
+ wirish_shift.cpp \
+ wirish_analog.cpp \
+ time.cpp \
+ pwm.cpp \
+ ext_interrupts.cpp \
+ wirish_digital.cpp \
+ boards.cpp
cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%)
cppFILES_$(d) := $(cppSRCS_$(d):%=$(d)/%)
diff --git a/wirish/time.c b/wirish/time.cpp
index c0a0649..c0a0649 100644
--- a/wirish/time.c
+++ b/wirish/time.cpp
diff --git a/wirish/time.h b/wirish/time.h
index 8d3d074..a0c0c82 100644
--- a/wirish/time.h
+++ b/wirish/time.h
@@ -35,10 +35,6 @@
#include "systick.h"
#include "boards.h"
-#ifdef __cplusplus
-extern "C"{
-#endif
-
#define US_PER_MS 1000
/**
@@ -99,10 +95,5 @@ void delay(unsigned long ms);
*/
void delayMicroseconds(uint32 us);
-#ifdef __cplusplus
-} // extern "C"
-#endif
-
-
#endif
diff --git a/wirish/wirish.c b/wirish/wirish.cpp
index 4c84d26..01f4507 100644
--- a/wirish/wirish.c
+++ b/wirish/wirish.cpp
@@ -59,7 +59,8 @@ void init(void) {
nvic_init();
systick_init(SYSTICK_RELOAD_VAL);
- gpio_init();
+ gpio_init_all();
+ afio_init();
/* Initialize the ADC for slow conversions, to allow for high
impedance inputs. */
@@ -74,7 +75,7 @@ void init(void) {
timer_init(TIMER5, 1);
timer_init(TIMER8, 1);
#endif
- setupUSB();
+ // setupUSB();
/* include the board-specific init macro */
BOARD_INIT;
diff --git a/wirish/wirish.h b/wirish/wirish.h
index 311c74f..447b2b6 100644
--- a/wirish/wirish.h
+++ b/wirish/wirish.h
@@ -32,25 +32,19 @@
#define _WIRISH_H_
#include "libmaple.h"
-#include "boards.h"
-#include "time.h"
#include "timers.h"
+
+#include "boards.h"
#include "io.h"
#include "bits.h"
#include "pwm.h"
#include "ext_interrupts.h"
#include "wirish_math.h"
-
-#ifdef __cplusplus
+#include "time.h"
#include "HardwareSPI.h"
#include "HardwareSerial.h"
#include "usb_serial.h"
#include "HardwareTimer.h"
-#endif
-
-#ifdef __cplusplus
-extern "C"{
-#endif
/* Arduino wiring macros and bit defines */
#define HIGH 0x1
@@ -77,9 +71,5 @@ typedef uint8 byte;
void init(void);
void shiftOut(uint8 dataPin, uint8 clockPin, uint8 bitOrder, byte val);
-#ifdef __cplusplus
-} // extern "C"
-#endif
-
#endif
diff --git a/wirish/wirish_analog.c b/wirish/wirish_analog.cpp
index a658184..a658184 100644
--- a/wirish/wirish_analog.c
+++ b/wirish/wirish_analog.cpp
diff --git a/wirish/wirish_digital.c b/wirish/wirish_digital.cpp
index bb28f0a..0c0bd85 100644
--- a/wirish/wirish_digital.c
+++ b/wirish/wirish_digital.cpp
@@ -30,7 +30,7 @@
#include "io.h"
void pinMode(uint8 pin, WiringPinMode mode) {
- uint8 outputMode;
+ gpio_pin_mode outputMode;
boolean pwm = false;
if (pin >= NR_GPIO_PINS) {
@@ -39,30 +39,30 @@ void pinMode(uint8 pin, WiringPinMode mode) {
switch(mode) {
case OUTPUT:
- outputMode = GPIO_MODE_OUTPUT_PP;
+ outputMode = GPIO_OUTPUT_PP;
break;
case OUTPUT_OPEN_DRAIN:
- outputMode = GPIO_MODE_OUTPUT_OD;
+ outputMode = GPIO_OUTPUT_OD;
break;
case INPUT:
case INPUT_FLOATING:
- outputMode = GPIO_MODE_INPUT_FLOATING;
+ outputMode = GPIO_INPUT_FLOATING;
break;
case INPUT_ANALOG:
- outputMode = GPIO_MODE_INPUT_ANALOG;
+ outputMode = GPIO_INPUT_ANALOG;
break;
case INPUT_PULLUP:
- outputMode = GPIO_MODE_INPUT_PU;
+ outputMode = GPIO_INPUT_PU;
break;
case INPUT_PULLDOWN:
- outputMode = GPIO_MODE_INPUT_PD;
+ outputMode = GPIO_INPUT_PD;
break;
case PWM:
- outputMode = GPIO_MODE_AF_OUTPUT_PP;
+ outputMode = GPIO_AF_OUTPUT_PP;
pwm = true;
break;
case PWM_OPEN_DRAIN:
- outputMode = GPIO_MODE_AF_OUTPUT_OD;
+ outputMode = GPIO_AF_OUTPUT_OD;
pwm = true;
break;
default:
@@ -70,7 +70,7 @@ void pinMode(uint8 pin, WiringPinMode mode) {
return;
}
- gpio_set_mode(PIN_MAP[pin].port, PIN_MAP[pin].pin, outputMode);
+ gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin, outputMode);
if (PIN_MAP[pin].timer_num != TIMER_INVALID) {
/* enable/disable timer channels if we're switching into or
@@ -93,7 +93,8 @@ uint32 digitalRead(uint8 pin) {
return 0;
}
- return gpio_read_bit(PIN_MAP[pin].port, PIN_MAP[pin].pin);
+ return gpio_read_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin) ?
+ HIGH : LOW;
}
void digitalWrite(uint8 pin, uint8 val) {
@@ -101,15 +102,15 @@ void digitalWrite(uint8 pin, uint8 val) {
return;
}
- gpio_write_bit(PIN_MAP[pin].port, PIN_MAP[pin].pin, val);
+ gpio_write_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin, val);
}
void togglePin(uint8 pin) {
if (pin >= NR_GPIO_PINS) {
return;
}
-
- gpio_toggle_pin(PIN_MAP[pin].port, PIN_MAP[pin].pin);
+
+ gpio_toggle_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].pin);
}
uint8 isButtonPressed() {
diff --git a/wirish/wirish_math.h b/wirish/wirish_math.h
index 14614ba..fa544a9 100644
--- a/wirish/wirish_math.h
+++ b/wirish/wirish_math.h
@@ -24,7 +24,7 @@
/**
* @file wirish_math.h
- * @brief Includes cmath; provides Arduino-compatible math routines.
+ * @brief Includes <math.h>; provides Arduino-compatible math routines.
*/
#ifndef _WIRING_MATH_H_
@@ -32,8 +32,6 @@
#include <math.h>
-#ifdef __cplusplus
-
/**
* @brief Initialize the pseudo-random number generator.
* @param seed the number used to initialize the seed; cannot be zero.
@@ -78,8 +76,7 @@ long random(long min, long max);
* @param toEnd the end of the value's mapped range.
* @return the mapped value.
*/
-/* TODO: profile code bloat due to inlining this */
-inline long map(long value, long fromStart, long fromEnd,
+static inline long map(long value, long fromStart, long fromEnd,
long toStart, long toEnd) {
return (value - fromStart) * (toEnd - toStart) / (fromEnd - fromStart) +
toStart;
@@ -105,8 +102,6 @@ inline long map(long value, long fromStart, long fromEnd,
#endif
#define abs(x) (((x) > 0) ? (x) : -(unsigned)(x))
-#endif
-
/* Following are duplicate declarations (with Doxygen comments) for
* some of the math.h functions; this is for the convenience of the
* Sphinx docs.
diff --git a/wirish/wirish_shift.c b/wirish/wirish_shift.cpp
index f67364d..f67364d 100644
--- a/wirish/wirish_shift.c
+++ b/wirish/wirish_shift.cpp