diff options
author | Marti Bolivar <mbolivar@leaflabs.com> | 2011-03-25 20:09:30 -0400 |
---|---|---|
committer | Marti Bolivar <mbolivar@leaflabs.com> | 2011-03-25 20:09:30 -0400 |
commit | f8081eeb04c9cb511adaf58e201c7cfbe1ddfbd4 (patch) | |
tree | a4de9665dd2d2340820b888c47e252c233ff9421 | |
parent | 63ea7464925b8cbeb8623d08a2bde0b1d2044047 (diff) | |
download | librambutan-f8081eeb04c9cb511adaf58e201c7cfbe1ddfbd4.tar.gz librambutan-f8081eeb04c9cb511adaf58e201c7cfbe1ddfbd4.zip |
Final stm32_pin_info design candidate; ADC3 support on Native.
Added an adc_dev to struct stm32_pin_info. This was necessary to add
support for the channels on the Native which are only connected to
ADC3, but it does add a bunch of NULLs to the PIN_MAPs.
I don't think any other peripherals need representation on a per-pin
basis. Each peripheral library will be responsible for keeping track
of related GPIO ports and bits, and we can throw #defines in to
boards/*.h for other things (e.g. BOARD_SPI1_MISO_PIN).
Fleshed out the ADC refactor and brought it more in keeping with the
new design as it evolves.
A couple of other tweaks. Notably: waitForButtonPress() now takes a
default argument meaning "wait forever".
Removed Maple-specific documentation from core functions in io.h; this
information will need to go into the individual board docs files.
-rw-r--r-- | examples/test-session.cpp | 50 | ||||
-rw-r--r-- | libmaple/adc.c | 65 | ||||
-rw-r--r-- | libmaple/adc.h | 294 | ||||
-rw-r--r-- | libmaple/timer.c | 4 | ||||
-rw-r--r-- | notes/coding_standard.txt | 44 | ||||
-rw-r--r-- | notes/pin-definitions.txt (renamed from notes/native-pin-definitions.txt) | 20 | ||||
-rw-r--r-- | wirish/boards.cpp (renamed from wirish/wirish.cpp) | 27 | ||||
-rw-r--r-- | wirish/boards.h | 16 | ||||
-rw-r--r-- | wirish/boards/maple.cpp | 78 | ||||
-rw-r--r-- | wirish/boards/maple_RET6.cpp | 81 | ||||
-rw-r--r-- | wirish/boards/maple_mini.cpp | 68 | ||||
-rw-r--r-- | wirish/boards/maple_native.cpp | 202 | ||||
-rw-r--r-- | wirish/ext_interrupts.cpp | 4 | ||||
-rw-r--r-- | wirish/io.h | 33 | ||||
-rw-r--r-- | wirish/pwm.cpp | 2 | ||||
-rw-r--r-- | wirish/rules.mk | 4 | ||||
-rw-r--r-- | wirish/wirish.h | 2 | ||||
-rw-r--r-- | wirish/wirish_analog.cpp | 9 | ||||
-rw-r--r-- | wirish/wirish_digital.cpp | 28 | ||||
-rw-r--r-- | wirish/wirish_types.h | 26 |
20 files changed, 653 insertions, 404 deletions
diff --git a/examples/test-session.cpp b/examples/test-session.cpp index 28c02f3..110b219 100644 --- a/examples/test-session.cpp +++ b/examples/test-session.cpp @@ -27,16 +27,13 @@ const uint8 adc_pins[] = #elif defined(BOARD_maple_mini) const uint8 pwm_pins[] = {3, 4, 5, 8, 9, 10, 11, 15, 16, 25, 26, 27}; -const uint8 adc_pins[] = {3, 4, 5, 6, 7, 8, 9, 10, 11, 33}; // NB: 33 is LED +const uint8 adc_pins[] = {3, 4, 5, 6, 7, 8, 9, 10, 11, 33}; #elif defined(BOARD_maple_native) const uint8 pwm_pins[] = {12, 13, 14, 15, 22, 23, 24, 25, 37, 38, 45, 46, 47, 48, 49, 50, 53, 54}; -const uint8 adc_pins[] = {6, 7, 8, 9, 10, 11, - /* the following are on ADC3, which lacks support: - 39, 40, 41, 42, 43, 45, */ +const uint8 adc_pins[] = {6, 7, 8, 9, 10, 11, 39, 40, 41, 42, 43, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54}; - #else #error "Board type has not been selected correctly" @@ -351,21 +348,34 @@ void cmd_everything(void) { // TODO void fast_gpio(int maple_pin) { gpio_dev *dev = PIN_MAP[maple_pin].gpio_device; - uint32 pin = PIN_MAP[maple_pin].gpio_pin; - - 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); + uint32 bit = PIN_MAP[maple_pin].gpio_bit; + + gpio_write_bit(dev, bit, 1); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); + gpio_toggle_bit(dev, bit); } void cmd_serial1_serial3(void) { diff --git a/libmaple/adc.c b/libmaple/adc.c index 3d38596..73dce0a 100644 --- a/libmaple/adc.c +++ b/libmaple/adc.c @@ -59,43 +59,44 @@ adc_dev adc3 = { const adc_dev *ADC3 = &adc3; #endif -static void adc_calibrate(const adc_dev *dev); - /** - * @brief Initialize an ADC peripheral. Only supports software triggered - * conversions. + * @brief Initialize an ADC peripheral. + * + * Initializes the RCC clock line for the given peripheral, using ADC + * prescaler RCC_ADCPRE_PCLK_DIV_6. Resets ADC device registers. + * * @param dev ADC peripheral to initialize - * @param flags unused */ -void adc_init(const adc_dev *dev, uint32 flags) { - /* Spin up the clocks */ +void adc_init(const adc_dev *dev) { rcc_set_prescaler(RCC_PRESCALER_ADC, RCC_ADCPRE_PCLK_DIV_6); rcc_clk_enable(dev->clk_id); rcc_reset_dev(dev->clk_id); - - /* Software triggers conversions, conversion on external events */ - adc_set_extsel(dev, 7); - adc_set_exttrig(dev, 1); - - /* Enable the ADC */ - adc_enable(dev); - - /* Calibrate ADC */ - adc_calibrate(dev); } /** * @brief Set external event select for regular group - * @param dev adc device - * @param trigger event to select. See ADC_CR2 EXTSEL[2:0] bits. + * @param dev ADC device + * @param event Event used to trigger the start of conversion. + * @see adc_extsel_event */ -void adc_set_extsel(const adc_dev *dev, uint8 trigger) { +void adc_set_extsel(const adc_dev *dev, adc_extsel_event event) { uint32 cr2 = dev->regs->CR2; cr2 &= ~ADC_CR2_EXTSEL; - cr2 |= (trigger & 0x7) << 17; + cr2 |= event; dev->regs->CR2 = cr2; } +/** + * @brief Call a function on all ADC devices. + * @param fn Function to call on each ADC device. + */ +void adc_foreach(void (*fn)(const adc_dev*)) { + fn(ADC1); + fn(ADC2); +#ifdef STM32_HIGH_DENSITY + fn(ADC3); +#endif +} /** * @brief Turn the given sample rate into values for ADC_SMPRx. Don't @@ -125,7 +126,7 @@ void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate) { * @brief Calibrate an ADC peripheral * @param dev adc device */ -static void adc_calibrate(const adc_dev *dev) { +void adc_calibrate(const adc_dev *dev) { __io uint32 *rstcal_bit = bb_perip(&(dev->regs->CR2), 3); __io uint32 *cal_bit = bb_perip(&(dev->regs->CR2), 2); @@ -137,3 +138,23 @@ static void adc_calibrate(const adc_dev *dev) { while (*cal_bit) ; } + +/** + * @brief Perform a single synchronous software triggered conversion on a + * channel. + * @param dev ADC device to use for reading. + * @param channel channel to convert + * @return conversion result + */ +uint16 adc_read(const adc_dev *dev, uint8 channel) { + adc_reg_map *regs = dev->regs; + + adc_set_reg_seqlen(dev, 1); + + regs->SQR3 = channel; + regs->CR2 |= ADC_CR2_SWSTART; + while(!(regs->SR & ADC_SR_EOC)) + ; + + return (uint16)(regs->DR & ADC_DR_DATA); +} diff --git a/libmaple/adc.h b/libmaple/adc.h index 53ef032..520b982 100644 --- a/libmaple/adc.h +++ b/libmaple/adc.h @@ -79,103 +79,253 @@ extern const adc_dev *ADC3; #endif /* - * ADC peripheral base addresses + * Register map base pointers */ /** ADC1 register map base pointer. */ -#define ADC1_BASE ((adc_reg_map*)0x40012400) +#define ADC1_BASE ((adc_reg_map*)0x40012400) /** ADC2 register map base pointer. */ -#define ADC2_BASE ((adc_reg_map*)0x40012800) +#define ADC2_BASE ((adc_reg_map*)0x40012800) /** ADC3 register map base pointer. */ -#define ADC3_BASE ((adc_reg_map*)0x40013C00) +#define ADC3_BASE ((adc_reg_map*)0x40013C00) /* * Register bit definitions */ /* Status register */ -#define ADC_SR_AWD BIT(0) -#define ADC_SR_EOC BIT(1) -#define ADC_SR_JEOC BIT(2) -#define ADC_SR_JSTRT BIT(3) -#define ADC_SR_STRT BIT(4) + +#define ADC_SR_AWD_BIT 0 +#define ADC_SR_EOC_BIT 1 +#define ADC_SR_JEOC_BIT 2 +#define ADC_SR_JSTRT_BIT 3 +#define ADC_SR_STRT_BIT 4 + +#define ADC_SR_AWD BIT(ADC_SR_AWD_BIT) +#define ADC_SR_EOC BIT(ADC_SR_EOC_BIT) +#define ADC_SR_JEOC BIT(ADC_SR_JEOC_BIT) +#define ADC_SR_JSTRT BIT(ADC_SR_JSTRT_BIT) +#define ADC_SR_STRT BIT(ADC_SR_STRT_BIT) /* Control register 1 */ -#define ADC_CR1_AWDCH (0x1F) -#define ADC_CR1_EOCIE BIT(5) -#define ADC_CR1_AWDIE BIT(6) -#define ADC_CR1_JEOCIE BIT(7) -#define ADC_CR1_SCAN BIT(8) -#define ADC_CR1_AWDSGL BIT(9) -#define ADC_CR1_JAUTO BIT(10) -#define ADC_CR1_DISCEN BIT(11) -#define ADC_CR1_JDISCEN BIT(12) -#define ADC_CR1_DISCNUM (0xE000) -#define ADC_CR1_JAWDEN BIT(22) -#define ADC_CR1_AWDEN BIT(23) + +#define ADC_CR1_EOCIE_BIT 5 +#define ADC_CR1_AWDIE_BIT 6 +#define ADC_CR1_JEOCIE_BIT 7 +#define ADC_CR1_SCAN_BIT 8 +#define ADC_CR1_AWDSGL_BIT 9 +#define ADC_CR1_JAUTO_BIT 10 +#define ADC_CR1_DISCEN_BIT 11 +#define ADC_CR1_JDISCEN_BIT 12 +#define ADC_CR1_JAWDEN_BIT 22 +#define ADC_CR1_AWDEN_BIT 23 + +#define ADC_CR1_AWDCH (0x1F) +#define ADC_CR1_EOCIE BIT(ADC_CR1_EOCIE_BIT) +#define ADC_CR1_AWDIE BIT(ADC_CR1_AWDIE_BIT) +#define ADC_CR1_JEOCIE BIT(ADC_CR1_JEOCIE_BIT) +#define ADC_CR1_SCAN BIT(ADC_CR1_SCAN_BIT) +#define ADC_CR1_AWDSGL BIT(ADC_CR1_AWDSGL_BIT) +#define ADC_CR1_JAUTO BIT(ADC_CR1_JAUTO_BIT) +#define ADC_CR1_DISCEN BIT(ADC_CR1_DISCEN_BIT) +#define ADC_CR1_JDISCEN BIT(ADC_CR1_JDISCEN_BIT) +#define ADC_CR1_DISCNUM (0xE000) +#define ADC_CR1_JAWDEN BIT(ADC_CR1_JAWDEN_BIT) +#define ADC_CR1_AWDEN BIT(ADC_CR1_AWDEN_BIT) /* Control register 2 */ -#define ADC_CR2_ADON BIT(0) -#define ADC_CR2_CONT BIT(1) -#define ADC_CR2_CAL BIT(2) -#define ADC_CR2_RSTCAL BIT(3) -#define ADC_CR2_DMA BIT(8) -#define ADC_CR2_ALIGN BIT(11) -#define ADC_CR2_JEXTSEL (0x7000) -#define ADC_CR2_JEXTTRIG BIT(15) -#define ADC_CR2_EXTSEL (0xE0000) -#define ADC_CR2_EXTTRIG BIT(20) -#define ADC_CR2_JSWSTART BIT(21) -#define ADC_CR2_SWSTART BIT(22) -#define ADC_CR2_TSEREFE BIT(23) - -void adc_init(const adc_dev *dev, uint32 flags); -void adc_set_extsel(const adc_dev *dev, uint8 trigger); -/** ADC per-sample conversion times, in ADC clock cycles */ -typedef enum { - ADC_SMPR_1_5, ///< 1.5 ADC cycles - ADC_SMPR_7_5, ///< 7.5 ADC cycles - ADC_SMPR_13_5, ///< 13.5 ADC cycles - ADC_SMPR_28_5, ///< 28.5 ADC cycles - ADC_SMPR_41_5, ///< 41.5 ADC cycles - ADC_SMPR_55_5, ///< 55.5 ADC cycles - ADC_SMPR_71_5, ///< 71.5 ADC cycles - ADC_SMPR_239_5 ///< 239.5 ADC cycles -} adc_smp_rate; +#define ADC_CR2_ADON_BIT 0 +#define ADC_CR2_CONT_BIT 1 +#define ADC_CR2_CAL_BIT 2 +#define ADC_CR2_RSTCAL_BIT 3 +#define ADC_CR2_DMA_BIT 8 +#define ADC_CR2_ALIGN_BIT 11 +#define ADC_CR2_JEXTTRIG_BIT 15 +#define ADC_CR2_EXTTRIG_BIT 20 +#define ADC_CR2_JSWSTART_BIT 21 +#define ADC_CR2_SWSTART_BIT 22 +#define ADC_CR2_TSEREFE_BIT 23 -void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate); +#define ADC_CR2_ADON BIT(ADC_CR2_ADON_BIT) +#define ADC_CR2_CONT BIT(ADC_CR2_CONT_BIT) +#define ADC_CR2_CAL BIT(ADC_CR2_CAL_BIT) +#define ADC_CR2_RSTCAL BIT(ADC_CR2_RSTCAL_BIT) +#define ADC_CR2_DMA BIT(ADC_CR2_DMA_BIT) +#define ADC_CR2_ALIGN BIT(ADC_CR2_ALIGN_BIT) +#define ADC_CR2_JEXTSEL (0x7000) +#define ADC_CR2_JEXTTRIG BIT(ADC_CR2_JEXTTRIG_BIT) +#define ADC_CR2_EXTSEL (0xE0000) +#define ADC_CR2_EXTTRIG BIT(ADC_CR2_EXTTRIG_BIT) +#define ADC_CR2_JSWSTART BIT(ADC_CR2_JSWSTART_BIT) +#define ADC_CR2_SWSTART BIT(ADC_CR2_SWSTART_BIT) +#define ADC_CR2_TSEREFE BIT(ADC_CR2_TSEREFE_BIT) + +/* Sample time register 1 */ + +#define ADC_SMPR1_SMP17 (0x7 << 21) +#define ADC_SMPR1_SMP16 (0x7 << 18) +#define ADC_SMPR1_SMP15 (0x7 << 15) +#define ADC_SMPR1_SMP14 (0x7 << 12) +#define ADC_SMPR1_SMP13 (0x7 << 9) +#define ADC_SMPR1_SMP12 (0x7 << 6) +#define ADC_SMPR1_SMP11 (0x7 << 3) +#define ADC_SMPR1_SMP10 0x7 + +/* Sample time register 2 */ + +#define ADC_SMPR2_SMP9 (0x7 << 27) +#define ADC_SMPR2_SMP8 (0x7 << 24) +#define ADC_SMPR2_SMP7 (0x7 << 21) +#define ADC_SMPR2_SMP6 (0x7 << 18) +#define ADC_SMPR2_SMP5 (0x7 << 15) +#define ADC_SMPR2_SMP4 (0x7 << 12) +#define ADC_SMPR2_SMP3 (0x7 << 9) +#define ADC_SMPR2_SMP2 (0x7 << 6) +#define ADC_SMPR2_SMP1 (0x7 << 3) +#define ADC_SMPR2_SMP0 0x7 + +/* Injected channel data offset register */ + +#define ADC_JOFR_JOFFSET 0x3FF + +/* Watchdog high threshold register */ + +#define ADC_HTR_HT 0x3FF + +/* Watchdog low threshold register */ + +#define ADC_LTR_LT 0x3FF + +/* Regular sequence register 1 */ + +#define ADC_SQR1_L (0x1F << 20) +#define ADC_SQR1_SQ16 (0x1F << 15) +#define ADC_SQR1_SQ15 (0x1F << 10) +#define ADC_SQR1_SQ14 (0x1F << 5) +#define ADC_SQR1_SQ13 0x1F + +/* Regular sequence register 2 */ + +#define ADC_SQR2_SQ12 (0x1F << 25) +#define ADC_SQR2_SQ11 (0x1F << 20) +#define ADC_SQR2_SQ10 (0x1F << 16) +#define ADC_SQR2_SQ9 (0x1F << 10) +#define ADC_SQR2_SQ8 (0x1F << 5) +#define ADC_SQR2_SQ7 0x1F + +/* Regular sequence register 3 */ + +#define ADC_SQR3_SQ6 (0x1F << 25) +#define ADC_SQR3_SQ5 (0x1F << 20) +#define ADC_SQR3_SQ4 (0x1F << 16) +#define ADC_SQR3_SQ3 (0x1F << 10) +#define ADC_SQR3_SQ2 (0x1F << 5) +#define ADC_SQR3_SQ1 0x1F + +/* Injected sequence register */ + +#define ADC_JSQR_JL (0x3 << 20) +#define ADC_JSQR_JL_1CONV (0x0 << 20) +#define ADC_JSQR_JL_2CONV (0x1 << 20) +#define ADC_JSQR_JL_3CONV (0x2 << 20) +#define ADC_JSQR_JL_4CONV (0x3 << 20) +#define ADC_JSQR_JSQ4 (0x1F << 15) +#define ADC_JSQR_JSQ3 (0x1F << 10) +#define ADC_JSQR_JSQ2 (0x1F << 5) +#define ADC_JSQR_JSQ1 0x1F + +/* Injected data registers */ + +#define ADC_JDR_JDATA 0xFFFF + +/* Regular data register */ + +#define ADC_DR_ADC2DATA (0xFFFF << 16) +#define ADC_DR_DATA 0xFFFF + +void adc_init(const adc_dev *dev); /** - * @brief Perform a single synchronous software triggered conversion on a - * channel. - * @param dev ADC device to use for reading. - * @param channel channel to convert - * @return conversion result + * @brief External event selector for regular group conversion. + * @see adc_set_extsel */ -static inline uint32 adc_read(const adc_dev *dev, uint8 channel) { - adc_reg_map *regs = dev->regs; +typedef enum adc_extsel_event { + ADC_ADC12_TIM1_CC1 = (0 << 17), /**< ADC1 and ADC2: Timer 1 CC1 event */ + ADC_ADC12_TIM1_CC2 = (1 << 17), /**< ADC1 and ADC2: Timer 1 CC2 event */ + ADC_ADC12_TIM1_CC3 = (2 << 17), /**< ADC1 and ADC2: Timer 1 CC3 event */ + ADC_ADC12_TIM2_CC2 = (3 << 17), /**< ADC1 and ADC2: Timer 2 CC2 event */ + ADC_ADC12_TIM3_TRGO = (4 << 17), /**< ADC1 and ADC2: Timer 3 TRGO event */ + ADC_ADC12_TIM4_CC4 = (5 << 17), /**< ADC1 and ADC2: Timer 4 CC4 event */ + ADC_ADC12_EXTI11 = (6 << 17), /**< ADC1 and ADC2: EXTI11 event */ +#ifdef STM32_HIGH_DENSITY + ADC_ADC12_TIM8_TRGO = (6 << 17), /**< ADC1 and ADC2: Timer 8 TRGO + event (high density only) */ +#endif + ADC_ADC12_SWSTART = (7 << 17), /**< ADC1 and ADC2: Software start */ +#ifdef STM32_HIGH_DENSITY + ADC_ADC3_TIM3_CC1 = (0 << 17), /**< ADC3: Timer 3 CC1 event + (high density only) */ + ADC_ADC3_TIM2_CC3 = (1 << 17), /**< ADC3: Timer 2 CC3 event + (high density only) */ + ADC_ADC3_TIM1_CC3 = (2 << 17), /**< ADC3: Timer 1 CC3 event + (high density only) */ + ADC_ADC3_TIM8_CC1 = (3 << 17), /**< ADC3: Timer 8 CC1 event + (high density only) */ + ADC_ADC3_TIM8_TRGO = (4 << 17), /**< ADC3: Timer 8 TRGO event + (high density only) */ + ADC_ADC3_TIM5_CC1 = (5 << 17), /**< ADC3: Timer 5 CC1 event + (high density only) */ + ADC_ADC3_TIM5_CC3 = (6 << 17), /**< ADC3: Timer 5 CC3 event + (high density only) */ + ADC_ADC3_SWSTART = (7 << 17), /**< ADC3: Software start (high + density only) */ +#endif + ADC_SWSTART = (7 << 17) /**< ADC1, ADC2, ADC3: Software start */ +} adc_extsel_event; - /* Set target channel */ - regs->SQR3 = channel; +void adc_set_extsel(const adc_dev *dev, adc_extsel_event event); +void adc_foreach(void (*fn)(const adc_dev*)); - /* Start the conversion */ - regs->CR2 |= ADC_CR2_SWSTART; +/** ADC per-sample conversion times, in ADC clock cycles */ +typedef enum { + ADC_SMPR_1_5, /**< 1.5 ADC cycles */ + ADC_SMPR_7_5, /**< 7.5 ADC cycles */ + ADC_SMPR_13_5, /**< 13.5 ADC cycles */ + ADC_SMPR_28_5, /**< 28.5 ADC cycles */ + ADC_SMPR_41_5, /**< 41.5 ADC cycles */ + ADC_SMPR_55_5, /**< 55.5 ADC cycles */ + ADC_SMPR_71_5, /**< 71.5 ADC cycles */ + ADC_SMPR_239_5 /**< 239.5 ADC cycles */ +} adc_smp_rate; - /* Wait for it to finish */ - while((regs->SR & ADC_SR_EOC) == 0) - ; +void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate); +void adc_calibrate(const adc_dev *dev); +uint16 adc_read(const adc_dev *dev, uint8 channel); - return regs->DR; +/** + * @brief Set the regular channel sequence length. + * + * Defines the total number of conversions in the regular channel + * conversion sequence. + * + * @param length Regular channel sequence length, from 1 to 16. + */ +static inline void adc_set_reg_seqlen(const adc_dev *dev, uint8 length) { + uint32 tmp = dev->regs->SQR1; + tmp &= ~ADC_SQR1_L; + tmp |= (length - 1) << 20; + dev->regs->SQR1 = tmp; } /** * @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 enable If 1, conversion on external events is enabled; if 0, + * disabled. */ static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) { - *bb_perip(&dev->regs->CR2, 20) = !!enable; + *bb_perip(&dev->regs->CR2, ADC_CR2_EXTTRIG_BIT) = !!enable; } /** @@ -183,7 +333,7 @@ static inline void adc_set_exttrig(const adc_dev *dev, uint8 enable) { * @param dev ADC device to enable */ static inline void adc_enable(const adc_dev *dev) { - *bb_perip(&dev->regs->CR2, 0) = 1; + *bb_perip(&dev->regs->CR2, ADC_CR2_ADON_BIT) = 1; } /** @@ -191,18 +341,14 @@ static inline void adc_enable(const adc_dev *dev) { * @param dev ADC device to disable */ static inline void adc_disable(const adc_dev *dev) { - *bb_perip(&dev->regs->CR2, 0) = 0; + *bb_perip(&dev->regs->CR2, ADC_CR2_ADON_BIT) = 0; } /** - * @brief Disable all ADCs + * @brief Disable all ADC peripherals. */ static inline void adc_disable_all(void) { - adc_disable(ADC1); - adc_disable(ADC2); -#ifdef STM32_HIGH_DENSITY - adc_disable(ADC3); -#endif + adc_foreach(adc_disable); } #ifdef __cplusplus diff --git a/libmaple/timer.c b/libmaple/timer.c index ad0ec6f..a4e4032 100644 --- a/libmaple/timer.c +++ b/libmaple/timer.c @@ -189,8 +189,8 @@ void timer_set_mode(timer_dev *dev, uint8 channel, timer_mode mode) { } /** - * @brief Call a given function on all timers. - * @param fn Function to call on each timer. + * @brief Call a function on timer devices. + * @param fn Function to call on each timer device. */ void timer_foreach(void (*fn)(timer_dev*)) { fn(TIMER1); diff --git a/notes/coding_standard.txt b/notes/coding_standard.txt index 372ebf4..b81847d 100644 --- a/notes/coding_standard.txt +++ b/notes/coding_standard.txt @@ -220,3 +220,47 @@ General Formatting (require 'lineker) (dolist (hook '(c-mode-hook c++-mode-hook)) (add-hook hook (lambda () (lineker-mode 1)))) + +Language Features and Compiler Extensions +----------------------------------------- + +- In libmaple proper, aim for C99 compatibility. Some GCC extensions + are OK, but let's not go crazy. + +- If you'd like to get code into libmaple which uses a GCC extension + not already in use elsewhere, ask a LeafLabs developer (or another + one, if you are one) what they think about it first. + +- Explicitly approved GCC extensions: + + * asm volatile: + http://gcc.gnu.org/onlinedocs/gcc/Extended-Asm.html + + * Nested functions: + http://gcc.gnu.org/onlinedocs/gcc/Nested-Functions.html + +- In wirish, generally be very conservative when using C++ features + that aren't part of C. We are forced to use C++ for Arduino + compatibility (and the general Arduino style of pretending that an + object is a library), but it's an angry beast, and we don't want to + provoke it. The mantra is "C with classes". + +- Explicitly approved C++ features: + + * Initializers that aren't constant; e.g. the gpio_dev* values in + PIN_MAPs. + + * Default arguments: e.g., the timeout argument defaulting to 0 + (meaning to wait forever) in waitForButtonPress(). + +- Explicitly forbidden C++ features: + + * Templates + +- C++ features that are conditionally allowed, but require explicit + approval from at least two libmaple developers (one of which may be + yourself): + + * Operator overloading: Never allowed when it's just for style. + Potentially allowed when you're implementing a class that models a + mathematical structure, and you'd like to implement e.g. operator+(). diff --git a/notes/native-pin-definitions.txt b/notes/pin-definitions.txt index b871f89..71572ac 100644 --- a/notes/native-pin-definitions.txt +++ b/notes/pin-definitions.txt @@ -1,4 +1,4 @@ -Maple Native (STM32F103ZE) pin definitions, by GPIO bank. +Pin definitions by GPIO bank. Source: ST DOC ID 14611, Datasheet for STM32F103xC, STM32F103xD, STM32F103xE, Table 5, pp. 30--35. @@ -9,13 +9,13 @@ bank's main table. Non-default alternate functions are not listed. If wirish will/does remap the pin's main function after reset, the main function is listed under "Other". -This document was prepared carefully and is believed to be complete -and correct, but the final arbiter of truth is the ST datasheet. +This document was prepared carefully and is believed to be correct, +but the final arbiter of truth is the ST datasheet. *** NB: UART 4 and 5 are NOT USART (columns are labeled appropriately). --------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C USART SPI DAC 5v? +GPIO ADC Timer FSMC I2S I2C USART SPI DAC 5v? --------------------------------------------------------------------------- PA0 123in0 2ch1etr - - - 2cts - - - 5ch1 @@ -52,7 +52,7 @@ PA14: JTCK-SWCLK (default) PA15: JTDI (default) ------------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C USART SPI DAC 5v? SDIO +GPIO ADC Timer FSMC I2S I2C USART SPI DAC 5v? SDIO ------------------------------------------------------------------------------- PB0 12in8 3ch3 - - - - - - - - 8ch2n @@ -80,7 +80,7 @@ PB3: JTDO (default) PB4: NJTRST (default) ------------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C UART SPI DAC 5v? SDIO +GPIO ADC Timer FSMC I2S I2C UART SPI DAC 5v? SDIO ------------------------------------------------------------------------------- PC0 123in10 - - - - - - - - - PC1 123in11 - - - - - - - - - @@ -106,7 +106,7 @@ PC14: OSC32_IN PC15: OSC32_OUT ------------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C UART SPI DAC 5v? SDIO +GPIO ADC Timer FSMC I2S I2C UART SPI DAC 5v? SDIO ------------------------------------------------------------------------------- PD0 - - D2 - - - - - Y - PD1 - - D3 - - - - - Y - @@ -132,7 +132,7 @@ PD0: OSC_IN (default) PD1: OSC_OUT (default) --------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C USART SPI DAC 5v? +GPIO ADC Timer FSMC I2S I2C USART SPI DAC 5v? --------------------------------------------------------------------------- PE0 - 4etr NBL0 - - - - - Y PE1 - - NBL1 - - - - - Y @@ -159,7 +159,7 @@ PE5: TRACED2 PE6: TRACED3 --------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C USART SPI DAC 5v? +GPIO ADC Timer FSMC I2S I2C USART SPI DAC 5v? --------------------------------------------------------------------------- PF0 - - A0 - - - - - Y PF1 - - A1 - - - - - Y @@ -179,7 +179,7 @@ PF14 - - A8 - - - - - Y PF15 - - A9 - - - - - Y --------------------------------------------------------------------------- -STM32 ADC Timer FSMC I2S I2C USART SPI DAC 5v? +GPIO ADC Timer FSMC I2S I2C USART SPI DAC 5v? --------------------------------------------------------------------------- PG0 - - A10 - - - - - Y PG1 - - A11 - - - - - Y diff --git a/wirish/wirish.cpp b/wirish/boards.cpp index aeed089..17f47c6 100644 --- a/wirish/wirish.cpp +++ b/wirish/boards.cpp @@ -23,7 +23,7 @@ *****************************************************************************/ /** - * @brief Generic Maple board initialization. + * @brief Generic board initialization routines. * * By default, we bring up all Maple boards to 72MHz, clocked off the * PLL, driven by the 8MHz external crystal. AHB and APB2 are clocked @@ -47,7 +47,13 @@ static void setupADC(void); static void setupTimers(void); /** - * Board-wide initialization function. Called before main(). + * @brief Generic board initialization function. + * + * This function is called before main(). It ensures that the clocks + * and peripherals are configured properly for use with wirish, then + * calls boardInit(). + * + * @see boardInit() */ void init(void) { setupFlash(); @@ -82,10 +88,10 @@ static void setupClocks() { rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1); } -/* TODO initialize more ADCs on high density boards. */ +static void adcDefaultConfig(const adc_dev* dev); + static void setupADC() { - adc_init(ADC1, 0); - adc_set_sample_rate(ADC1, ADC_SMPR_55_5); // for high impedance inputs + adc_foreach(adcDefaultConfig); } static void timerDefaultConfig(timer_dev*); @@ -94,6 +100,17 @@ static void setupTimers() { timer_foreach(timerDefaultConfig); } +static void adcDefaultConfig(const adc_dev *dev) { + adc_init(dev); + + adc_set_extsel(dev, ADC_SWSTART); + adc_set_exttrig(dev, true); + + adc_enable(dev); + adc_calibrate(dev); + adc_set_sample_rate(dev, ADC_SMPR_55_5); +} + static void timerDefaultConfig(timer_dev *dev) { timer_adv_reg_map *regs = (dev->regs).adv; const uint16 full_overflow = 0xFFFF; diff --git a/wirish/boards.h b/wirish/boards.h index b72609d..3d023ae 100644 --- a/wirish/boards.h +++ b/wirish/boards.h @@ -60,12 +60,22 @@ enum { D106, D107, D108, D109, D110, D111, }; /** - * @brief Maps each pin to a corresponding struct stm32_pin_info. - * @see struct stm32_pin_info + * @brief Maps each Maple pin to a corresponding stm32_pin_info. + * @see stm32_pin_info */ extern stm32_pin_info PIN_MAP[]; -/** Board-specific initialization function. */ +void init(void); + +/** + * @brief Board-specific initialization function. + * + * This function is called from init() after all generic board + * initialization has been performed. Each board is required to + * define its own. + * + * @see init() + */ extern void boardInit(void); #ifdef BOARD_maple diff --git a/wirish/boards/maple.cpp b/wirish/boards/maple.cpp index cebd222..ba2261b 100644 --- a/wirish/boards/maple.cpp +++ b/wirish/boards/maple.cpp @@ -44,51 +44,51 @@ stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { /* Top header */ - {GPIOA, TIMER2, 3, 4, 3}, /* D0/PA3 */ - {GPIOA, TIMER2, 2, 3, 2}, /* D1/PA2 */ - {GPIOA, TIMER2, 0, 1, 0}, /* D2/PA0 */ - {GPIOA, TIMER2, 1, 2, 1}, /* D3/PA1 */ - {GPIOB, NULL, 5, 0, ADCx}, /* D4/PB5 */ - {GPIOB, TIMER4, 6, 1, ADCx}, /* D5/PB6 */ - {GPIOA, TIMER1, 8, 1, ADCx}, /* D6/PA8 */ - {GPIOA, TIMER1, 9, 2, ADCx}, /* D7/PA9 */ - {GPIOA, TIMER1, 10, 3, ADCx}, /* D8/PA10 */ - {GPIOB, TIMER4, 7, 2, ADCx}, /* D9/PB7 */ - {GPIOA, NULL, 4, 0, 4}, /* D10/PA4 */ - {GPIOA, TIMER3, 7, 2, 7}, /* D11/PA7 */ - {GPIOA, TIMER3, 6, 1, 6}, /* D12/PA6 */ - {GPIOA, NULL, 5, 0, 5}, /* D13/PA5 (LED) */ - {GPIOB, TIMER4, 8, 3, ADCx}, /* D14/PB8 */ + {GPIOA, TIMER2, ADC1, 3, 4, 3}, /* D0/PA3 */ + {GPIOA, TIMER2, ADC1, 2, 3, 2}, /* D1/PA2 */ + {GPIOA, TIMER2, ADC1, 0, 1, 0}, /* D2/PA0 */ + {GPIOA, TIMER2, ADC1, 1, 2, 1}, /* D3/PA1 */ + {GPIOB, NULL, NULL, 5, 0, ADCx}, /* D4/PB5 */ + {GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D5/PB6 */ + {GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* D6/PA8 */ + {GPIOA, TIMER1, NULL, 9, 2, ADCx}, /* D7/PA9 */ + {GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* D8/PA10 */ + {GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* D9/PB7 */ + {GPIOA, NULL, ADC1, 4, 0, 4}, /* D10/PA4 */ + {GPIOA, TIMER3, ADC1, 7, 2, 7}, /* D11/PA7 */ + {GPIOA, TIMER3, ADC1, 6, 1, 6}, /* D12/PA6 */ + {GPIOA, NULL, ADC1, 5, 0, 5}, /* D13/PA5 (LED) */ + {GPIOB, TIMER4, NULL, 8, 3, ADCx}, /* D14/PB8 */ /* Little header */ - {GPIOC, NULL, 0, 0, 10}, /* D15/PC0 */ - {GPIOC, NULL, 1, 0, 11}, /* D16/PC1 */ - {GPIOC, NULL, 2, 0, 12}, /* D17/PC2 */ - {GPIOC, NULL, 3, 0, 13}, /* D18/PC3 */ - {GPIOC, NULL, 4, 0, 14}, /* D19/PC4 */ - {GPIOC, NULL, 5, 0, 15}, /* D20/PC5 */ + {GPIOC, NULL, ADC1, 0, 0, 10}, /* D15/PC0 */ + {GPIOC, NULL, ADC1, 1, 0, 11}, /* D16/PC1 */ + {GPIOC, NULL, ADC1, 2, 0, 12}, /* D17/PC2 */ + {GPIOC, NULL, ADC1, 3, 0, 13}, /* D18/PC3 */ + {GPIOC, NULL, ADC1, 4, 0, 14}, /* D19/PC4 */ + {GPIOC, NULL, ADC1, 5, 0, 15}, /* D20/PC5 */ /* External header */ - {GPIOC, NULL, 13, 0, ADCx}, /* D21/PC13 */ - {GPIOC, NULL, 14, 0, ADCx}, /* D22/PC14 */ - {GPIOC, NULL, 15, 0, ADCx}, /* D23/PC15 */ - {GPIOB, TIMER4, 9, 4, ADCx}, /* D24/PB9 */ - {GPIOD, NULL, 2, 0, ADCx}, /* D25/PD2 */ - {GPIOC, NULL, 10, 0, ADCx}, /* D26/PC10 */ - {GPIOB, TIMER3, 0, 3, 8}, /* D27/PB0 */ - {GPIOB, TIMER3, 1, 4, 9}, /* D28/PB1 */ - {GPIOB, NULL, 10, 0, ADCx}, /* D29/PB10 */ - {GPIOB, NULL, 11, 0, ADCx}, /* D30/PB11 */ - {GPIOB, NULL, 12, 0, ADCx}, /* D31/PB12 */ - {GPIOB, NULL, 13, 0, ADCx}, /* D32/PB13 */ - {GPIOB, NULL, 14, 0, ADCx}, /* D33/PB14 */ - {GPIOB, NULL, 15, 0, ADCx}, /* D34/PB15 */ - {GPIOC, NULL, 6, 0, ADCx}, /* D35/PC6 */ - {GPIOC, NULL, 7, 0, ADCx}, /* D36/PC7 */ - {GPIOC, NULL, 8, 0, ADCx}, /* D37/PC8 */ - {GPIOC, NULL, 9, 0, ADCx} /* D38/PC9 (BUT) */ + {GPIOC, NULL, NULL, 13, 0, ADCx}, /* D21/PC13 */ + {GPIOC, NULL, NULL, 14, 0, ADCx}, /* D22/PC14 */ + {GPIOC, NULL, NULL, 15, 0, ADCx}, /* D23/PC15 */ + {GPIOB, TIMER4, NULL, 9, 4, ADCx}, /* D24/PB9 */ + {GPIOD, NULL, NULL, 2, 0, ADCx}, /* D25/PD2 */ + {GPIOC, NULL, NULL, 10, 0, ADCx}, /* D26/PC10 */ + {GPIOB, TIMER3, ADC1, 0, 3, 8}, /* D27/PB0 */ + {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D28/PB1 */ + {GPIOB, NULL, NULL, 10, 0, ADCx}, /* D29/PB10 */ + {GPIOB, NULL, NULL, 11, 0, ADCx}, /* D30/PB11 */ + {GPIOB, NULL, NULL, 12, 0, ADCx}, /* D31/PB12 */ + {GPIOB, NULL, NULL, 13, 0, ADCx}, /* D32/PB13 */ + {GPIOB, NULL, NULL, 14, 0, ADCx}, /* D33/PB14 */ + {GPIOB, NULL, NULL, 15, 0, ADCx}, /* D34/PB15 */ + {GPIOC, NULL, NULL, 6, 0, ADCx}, /* D35/PC6 */ + {GPIOC, NULL, NULL, 7, 0, ADCx}, /* D36/PC7 */ + {GPIOC, NULL, NULL, 8, 0, ADCx}, /* D37/PC8 */ + {GPIOC, NULL, NULL, 9, 0, ADCx} /* D38/PC9 (BUT) */ }; #endif diff --git a/wirish/boards/maple_RET6.cpp b/wirish/boards/maple_RET6.cpp index ae31ce3..962affc 100644 --- a/wirish/boards/maple_RET6.cpp +++ b/wirish/boards/maple_RET6.cpp @@ -38,51 +38,54 @@ void boardInit(void) { } stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { - {GPIOA, TIMER2, 3, 4, 3}, /* D0/PA3 */ - {GPIOA, TIMER2, 2, 3, 2}, /* D1/PA2 */ - {GPIOA, TIMER2, 0, 1, 0}, /* D2/PA0 */ - {GPIOA, TIMER2, 1, 2, 1}, /* D3/PA1 */ - {GPIOB, NULL, 5, 0, ADCx}, /* D4/PB5 */ - {GPIOB, TIMER4, 6, 1, ADCx}, /* D5/PB6 */ - {GPIOA, TIMER1, 8, 1, ADCx}, /* D6/PA8 */ - {GPIOA, TIMER1, 9, 2, ADCx}, /* D7/PA9 */ - {GPIOA, TIMER1, 10, 3, ADCx}, /* D8/PA10 */ - {GPIOB, TIMER4, 7, 2, ADCx}, /* D9/PB7 */ - {GPIOA, NULL, 4, 0, 4}, /* D10/PA4 */ - {GPIOA, TIMER3, 7, 2, 7}, /* D11/PA7 */ - {GPIOA, TIMER3, 6, 1, 6}, /* D12/PA6 */ - {GPIOA, NULL, 5, 0, 5}, /* D13/PA5 (LED) */ - {GPIOB, TIMER4, 8, 3, ADCx}, /* D14/PB8 */ + + /* Top header */ + + {GPIOA, TIMER2, ADC1, 3, 4, 3}, /* D0/PA3 */ + {GPIOA, TIMER2, ADC1, 2, 3, 2}, /* D1/PA2 */ + {GPIOA, TIMER2, ADC1, 0, 1, 0}, /* D2/PA0 */ + {GPIOA, TIMER2, ADC1, 1, 2, 1}, /* D3/PA1 */ + {GPIOB, NULL, NULL, 5, 0, ADCx}, /* D4/PB5 */ + {GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D5/PB6 */ + {GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* D6/PA8 */ + {GPIOA, TIMER1, NULL, 9, 2, ADCx}, /* D7/PA9 */ + {GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* D8/PA10 */ + {GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* D9/PB7 */ + {GPIOA, NULL, ADC1, 4, 0, 4}, /* D10/PA4 */ + {GPIOA, TIMER3, ADC1, 7, 2, 7}, /* D11/PA7 */ + {GPIOA, TIMER3, ADC1, 6, 1, 6}, /* D12/PA6 */ + {GPIOA, NULL, ADC1, 5, 0, 5}, /* D13/PA5 (LED) */ + {GPIOB, TIMER4, NULL, 8, 3, ADCx}, /* D14/PB8 */ /* Little header */ - {GPIOC, NULL, 0, 0, 10}, /* D15/PC0 */ - {GPIOC, NULL, 1, 0, 11}, /* D16/PC1 */ - {GPIOC, NULL, 2, 0, 12}, /* D17/PC2 */ - {GPIOC, NULL, 3, 0, 13}, /* D18/PC3 */ - {GPIOC, NULL, 4, 0, 14}, /* D19/PC4 */ - {GPIOC, NULL, 5, 0, 15}, /* D20/PC5 */ + {GPIOC, NULL, ADC1, 0, 0, 10}, /* D15/PC0 */ + {GPIOC, NULL, ADC1, 1, 0, 11}, /* D16/PC1 */ + {GPIOC, NULL, ADC1, 2, 0, 12}, /* D17/PC2 */ + {GPIOC, NULL, ADC1, 3, 0, 13}, /* D18/PC3 */ + {GPIOC, NULL, ADC1, 4, 0, 14}, /* D19/PC4 */ + {GPIOC, NULL, ADC1, 5, 0, 15}, /* D20/PC5 */ /* External header */ - {GPIOC, NULL, 13, 0, ADCx}, /* D21/PC13 */ - {GPIOC, NULL, 14, 0, ADCx}, /* D22/PC14 */ - {GPIOC, NULL, 15, 0, ADCx}, /* D23/PC15 */ - {GPIOB, TIMER4, 9, 4, ADCx}, /* D24/PB9 */ - {GPIOD, NULL, 2, 0, ADCx}, /* D25/PD2 */ - {GPIOC, NULL, 10, 0, ADCx}, /* D26/PC10 */ - {GPIOB, TIMER3, 0, 3, 8}, /* D27/PB0 */ - {GPIOB, TIMER3, 1, 4, 9}, /* D28/PB1 */ - {GPIOB, NULL, 10, 0, ADCx}, /* D29/PB10 */ - {GPIOB, NULL, 11, 0, ADCx}, /* D30/PB11 */ - {GPIOB, NULL, 12, 0, ADCx}, /* D31/PB12 */ - {GPIOB, NULL, 13, 0, ADCx}, /* D32/PB13 */ - {GPIOB, NULL, 14, 0, ADCx}, /* D33/PB14 */ - {GPIOB, NULL, 15, 0, ADCx}, /* D34/PB15 */ - {GPIOC, TIMER8, 6, 1, ADCx}, /* D35/PC6 */ - {GPIOC, TIMER8, 7, 2, ADCx}, /* D36/PC7 */ - {GPIOC, TIMER8, 8, 3, ADCx}, /* D37/PC8 */ - {GPIOC, TIMER8, 9, 4, ADCx} /* D38/PC9 (BUT) */ + {GPIOC, NULL, NULL, 13, 0, ADCx}, /* D21/PC13 */ + {GPIOC, NULL, NULL, 14, 0, ADCx}, /* D22/PC14 */ + {GPIOC, NULL, NULL, 15, 0, ADCx}, /* D23/PC15 */ + {GPIOB, TIMER4, NULL, 9, 4, ADCx}, /* D24/PB9 */ + {GPIOD, NULL, NULL, 2, 0, ADCx}, /* D25/PD2 */ + {GPIOC, NULL, NULL, 10, 0, ADCx}, /* D26/PC10 */ + {GPIOB, TIMER3, ADC1, 0, 3, 8}, /* D27/PB0 */ + {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D28/PB1 */ + {GPIOB, NULL, NULL, 10, 0, ADCx}, /* D29/PB10 */ + {GPIOB, NULL, NULL, 11, 0, ADCx}, /* D30/PB11 */ + {GPIOB, NULL, NULL, 12, 0, ADCx}, /* D31/PB12 */ + {GPIOB, NULL, NULL, 13, 0, ADCx}, /* D32/PB13 */ + {GPIOB, NULL, NULL, 14, 0, ADCx}, /* D33/PB14 */ + {GPIOB, NULL, NULL, 15, 0, ADCx}, /* D34/PB15 */ + {GPIOC, TIMER8, NULL, 6, 1, ADCx}, /* D35/PC6 */ + {GPIOC, TIMER8, NULL, 7, 2, ADCx}, /* D36/PC7 */ + {GPIOC, TIMER8, NULL, 8, 3, ADCx}, /* D37/PC8 */ + {GPIOC, TIMER8, NULL, 9, 4, ADCx} /* D38/PC9 (BUT) */ }; #endif diff --git a/wirish/boards/maple_mini.cpp b/wirish/boards/maple_mini.cpp index 8c005cf..66a0997 100644 --- a/wirish/boards/maple_mini.cpp +++ b/wirish/boards/maple_mini.cpp @@ -45,43 +45,43 @@ stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { /* Top header */ - {GPIOB, NULL, 11, 0, ADCx}, /* D0/PB11 */ - {GPIOB, NULL, 10, 0, ADCx}, /* D1/PB10 */ - {GPIOB, NULL, 2, 0, ADCx}, /* D2/PB2 */ - {GPIOB, TIMER3, 0, 3, 8}, /* D3/PB0 */ - {GPIOA, TIMER3, 7, 2, 7}, /* D4/PA7 */ - {GPIOA, TIMER3, 6, 1, 6}, /* D5/PA6 */ - {GPIOA, NULL, 5, 0, 5}, /* D6/PA5 */ - {GPIOA, NULL, 4, 0, 4}, /* D7/PA4 */ - {GPIOA, TIMER2, 3, 4, 3}, /* D8/PA3 */ - {GPIOA, TIMER2, 2, 3, 2}, /* D9/PA2 */ - {GPIOA, TIMER2, 1, 2, 1}, /* D10/PA1 */ - {GPIOA, TIMER2, 0, 1, 0}, /* D11/PA0 */ - {GPIOC, NULL, 15, 0, ADCx}, /* D12/PC15 */ - {GPIOC, NULL, 14, 0, ADCx}, /* D13/PC14 */ - {GPIOC, NULL, 13, 0, ADCx}, /* D14/PC13 */ + {GPIOB, NULL, NULL, 11, 0, ADCx}, /* D0/PB11 */ + {GPIOB, NULL, NULL, 10, 0, ADCx}, /* D1/PB10 */ + {GPIOB, NULL, NULL, 2, 0, ADCx}, /* D2/PB2 */ + {GPIOB, TIMER3, ADC1, 0, 3, 8}, /* D3/PB0 */ + {GPIOA, TIMER3, ADC1, 7, 2, 7}, /* D4/PA7 */ + {GPIOA, TIMER3, ADC1, 6, 1, 6}, /* D5/PA6 */ + {GPIOA, NULL, ADC1, 5, 0, 5}, /* D6/PA5 */ + {GPIOA, NULL, ADC1, 4, 0, 4}, /* D7/PA4 */ + {GPIOA, TIMER2, ADC1, 3, 4, 3}, /* D8/PA3 */ + {GPIOA, TIMER2, ADC1, 2, 3, 2}, /* D9/PA2 */ + {GPIOA, TIMER2, ADC1, 1, 2, 1}, /* D10/PA1 */ + {GPIOA, TIMER2, ADC1, 0, 1, 0}, /* D11/PA0 */ + {GPIOC, NULL, NULL, 15, 0, ADCx}, /* D12/PC15 */ + {GPIOC, NULL, NULL, 14, 0, ADCx}, /* D13/PC14 */ + {GPIOC, NULL, NULL, 13, 0, ADCx}, /* D14/PC13 */ /* Bottom header */ - {GPIOB, TIMER4, 7, 2, ADCx}, /* D15/PB7 */ - {GPIOB, TIMER4, 6, 1, ADCx}, /* D16/PB6 */ - {GPIOB, NULL, 5, 0, ADCx}, /* D17/PB5 */ - {GPIOB, NULL, 4, 0, ADCx}, /* D18/PB4 */ - {GPIOB, NULL, 3, 0, ADCx}, /* D19/PB3 */ - {GPIOA, NULL, 15, 0, ADCx}, /* D20/PA15 */ - {GPIOA, NULL, 14, 0, ADCx}, /* D21/PA14 */ - {GPIOA, NULL, 13, 0, ADCx}, /* D22/PA13 */ - {GPIOA, NULL, 12, 0, ADCx}, /* D23/PA12 */ - {GPIOA, TIMER1, 11, 4, ADCx}, /* D24/PA11 */ - {GPIOA, TIMER1, 10, 3, ADCx}, /* D25/PA10 */ - {GPIOA, TIMER2, 9, 2, ADCx}, /* D26/PA9 */ - {GPIOA, TIMER1, 8, 1, ADCx}, /* D27/PA8 */ - {GPIOB, NULL, 15, 0, ADCx}, /* D28/PB15 */ - {GPIOB, NULL, 14, 0, ADCx}, /* D29/PB14 */ - {GPIOB, NULL, 13, 0, ADCx}, /* D30/PB13 */ - {GPIOB, NULL, 12, 0, ADCx}, /* D31/PB12 */ - {GPIOB, TIMER4, 8, 3, ADCx}, /* D32/PB8 */ - {GPIOB, TIMER3, 1, 4, 9}, /* D33/PB1 */ + {GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* D15/PB7 */ + {GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D16/PB6 */ + {GPIOB, NULL, NULL, 5, 0, ADCx}, /* D17/PB5 */ + {GPIOB, NULL, NULL, 4, 0, ADCx}, /* D18/PB4 */ + {GPIOB, NULL, NULL, 3, 0, ADCx}, /* D19/PB3 */ + {GPIOA, NULL, NULL, 15, 0, ADCx}, /* D20/PA15 */ + {GPIOA, NULL, NULL, 14, 0, ADCx}, /* D21/PA14 */ + {GPIOA, NULL, NULL, 13, 0, ADCx}, /* D22/PA13 */ + {GPIOA, NULL, NULL, 12, 0, ADCx}, /* D23/PA12 */ + {GPIOA, TIMER1, NULL, 11, 4, ADCx}, /* D24/PA11 */ + {GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* D25/PA10 */ + {GPIOA, TIMER2, NULL, 9, 2, ADCx}, /* D26/PA9 */ + {GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* D27/PA8 */ + {GPIOB, NULL, NULL, 15, 0, ADCx}, /* D28/PB15 */ + {GPIOB, NULL, NULL, 14, 0, ADCx}, /* D29/PB14 */ + {GPIOB, NULL, NULL, 13, 0, ADCx}, /* D30/PB13 */ + {GPIOB, NULL, NULL, 12, 0, ADCx}, /* D31/PB12 */ + {GPIOB, TIMER4, NULL, 8, 3, ADCx}, /* D32/PB8 */ + {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D33/PB1 */ }; #endif diff --git a/wirish/boards/maple_native.cpp b/wirish/boards/maple_native.cpp index c04e98f..75c6a2d 100644 --- a/wirish/boards/maple_native.cpp +++ b/wirish/boards/maple_native.cpp @@ -43,113 +43,113 @@ stm32_pin_info PIN_MAP[NR_GPIO_PINS] = { /* Top header */ - {GPIOB, NULL, 10, 0, ADCx}, /* D0/PB10 */ - {GPIOB, NULL, 2, 0, ADCx}, /* D1/PB2 */ - {GPIOB, NULL, 12, 0, ADCx}, /* D2/PB12 */ - {GPIOB, NULL, 13, 0, ADCx}, /* D3/PB13 */ - {GPIOB, NULL, 14, 0, ADCx}, /* D4/PB14 */ - {GPIOB, NULL, 15, 0, ADCx}, /* D5/PB15 */ - {GPIOC, NULL, 0, 0, 10}, /* D6/PC0 */ - {GPIOC, NULL, 1, 0, 11}, /* D7/PC1 */ - {GPIOC, NULL, 2, 0, 12}, /* D8/PC2 */ - {GPIOC, NULL, 3, 0, 13}, /* D9/PC3 */ - {GPIOC, NULL, 4, 0, 14}, /* D10/PC4 */ - {GPIOC, NULL, 5, 0, 15}, /* D11/PC5 */ - {GPIOC, TIMER8, 6, 1, ADCx}, /* D12/PC6 */ - {GPIOC, TIMER8, 7, 2, ADCx}, /* D13/PC7 */ - {GPIOC, TIMER8, 8, 3, ADCx}, /* D14/PC8 */ - {GPIOC, TIMER8, 9, 4, ADCx}, /* D15/PC9 */ - {GPIOC, NULL, 10, 0, ADCx}, /* D16/PC10 */ - {GPIOC, NULL, 11, 0, ADCx}, /* D17/PC11 */ - {GPIOC, NULL, 12, 0, ADCx}, /* D18/PC12 */ - {GPIOC, NULL, 13, 0, ADCx}, /* D19/PC13 */ - {GPIOC, NULL, 14, 0, ADCx}, /* D20/PC14 */ - {GPIOC, NULL, 15, 0, ADCx}, /* D21/PC15 */ - {GPIOA, TIMER1, 8, 1, ADCx}, /* D22/PA8 */ - {GPIOA, TIMER1, 9, 2, ADCx}, /* D23/PA9 */ - {GPIOA, TIMER1, 10, 3, ADCx}, /* D24/PA10 */ - {GPIOB, TIMER4, 9, 4, ADCx}, /* D25/PB9 */ + {GPIOB, NULL, NULL, 10, 0, ADCx}, /* D0/PB10 */ + {GPIOB, NULL, NULL, 2, 0, ADCx}, /* D1/PB2 */ + {GPIOB, NULL, NULL, 12, 0, ADCx}, /* D2/PB12 */ + {GPIOB, NULL, NULL, 13, 0, ADCx}, /* D3/PB13 */ + {GPIOB, NULL, NULL, 14, 0, ADCx}, /* D4/PB14 */ + {GPIOB, NULL, NULL, 15, 0, ADCx}, /* D5/PB15 */ + {GPIOC, NULL, ADC1, 0, 0, 10}, /* D6/PC0 */ + {GPIOC, NULL, ADC1, 1, 0, 11}, /* D7/PC1 */ + {GPIOC, NULL, ADC1, 2, 0, 12}, /* D8/PC2 */ + {GPIOC, NULL, ADC1, 3, 0, 13}, /* D9/PC3 */ + {GPIOC, NULL, ADC1, 4, 0, 14}, /* D10/PC4 */ + {GPIOC, NULL, ADC1, 5, 0, 15}, /* D11/PC5 */ + {GPIOC, TIMER8, NULL, 6, 1, ADCx}, /* D12/PC6 */ + {GPIOC, TIMER8, NULL, 7, 2, ADCx}, /* D13/PC7 */ + {GPIOC, TIMER8, NULL, 8, 3, ADCx}, /* D14/PC8 */ + {GPIOC, TIMER8, NULL, 9, 4, ADCx}, /* D15/PC9 */ + {GPIOC, NULL, NULL, 10, 0, ADCx}, /* D16/PC10 */ + {GPIOC, NULL, NULL, 11, 0, ADCx}, /* D17/PC11 */ + {GPIOC, NULL, NULL, 12, 0, ADCx}, /* D18/PC12 */ + {GPIOC, NULL, NULL, 13, 0, ADCx}, /* D19/PC13 */ + {GPIOC, NULL, NULL, 14, 0, ADCx}, /* D20/PC14 */ + {GPIOC, NULL, NULL, 15, 0, ADCx}, /* D21/PC15 */ + {GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* D22/PA8 */ + {GPIOA, TIMER1, NULL, 9, 2, ADCx}, /* D23/PA9 */ + {GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* D24/PA10 */ + {GPIOB, TIMER4, NULL, 9, 4, ADCx}, /* D25/PB9 */ /* Bottom header */ - /* FIXME (?) What about D48--D50 also being TIMER2_CH[234]? */ + /* Note: D{48, 49, 50} are also TIMER2_CH{2, 3, 4}, respectively. */ - {GPIOD, NULL, 2, 0, ADCx}, /* D26/PD2 */ - {GPIOD, NULL, 3, 0, ADCx}, /* D27/PD3 */ - {GPIOD, NULL, 6, 0, ADCx}, /* D28/PD6 */ - {GPIOG, NULL, 11, 0, ADCx}, /* D29/PG11 */ - {GPIOG, NULL, 12, 0, ADCx}, /* D30/PG12 */ - {GPIOG, NULL, 13, 0, ADCx}, /* D31/PG13 */ - {GPIOG, NULL, 14, 0, ADCx}, /* D32/PG14 */ - {GPIOG, NULL, 8, 0, ADCx}, /* D33/PG8 */ - {GPIOG, NULL, 7, 0, ADCx}, /* D34/PG7 */ - {GPIOG, NULL, 6, 0, ADCx}, /* D35/PG6 */ - {GPIOB, NULL, 5, 0, ADCx}, /* D36/PB5 */ - {GPIOB, TIMER4, 6, 1, ADCx}, /* D37/PB6 */ - {GPIOB, TIMER4, 7, 2, ADCx}, /* D38/PB7 */ - {GPIOF, NULL, 6, 0, 4}, /* D39/PF6 */ - {GPIOF, NULL, 7, 0, 5}, /* D40/PF7 */ - {GPIOF, NULL, 8, 0, 6}, /* D41/PF8 */ - {GPIOF, NULL, 9, 0, 7}, /* D42/PF9 */ - {GPIOF, NULL, 10, 0, 8}, /* D43/PF10 */ - {GPIOF, NULL, 11, 0, ADCx}, /* D44/PF11 */ - {GPIOB, TIMER3, 1, 4, 9}, /* D45/PB1 */ - {GPIOB, TIMER3, 0, 3, 8}, /* D46/PB0 */ - {GPIOA, TIMER5, 0, 1, 0}, /* D47/PA0 */ - {GPIOA, TIMER5, 1, 2, 1}, /* D48/PA1 */ - {GPIOA, TIMER5, 2, 3, 2}, /* D49/PA2 */ - {GPIOA, TIMER5, 3, 4, 3}, /* D50/PA3 */ - {GPIOA, NULL, 4, 0, 4}, /* D51/PA4 */ - {GPIOA, NULL, 5, 0, 5}, /* D52/PA5 */ - {GPIOA, TIMER3, 6, 1, 6}, /* D53/PA6 */ - {GPIOA, TIMER3, 7, 2, 7}, /* D54/PA7 */ + {GPIOD, NULL, NULL, 2, 0, ADCx}, /* D26/PD2 */ + {GPIOD, NULL, NULL, 3, 0, ADCx}, /* D27/PD3 */ + {GPIOD, NULL, NULL, 6, 0, ADCx}, /* D28/PD6 */ + {GPIOG, NULL, NULL, 11, 0, ADCx}, /* D29/PG11 */ + {GPIOG, NULL, NULL, 12, 0, ADCx}, /* D30/PG12 */ + {GPIOG, NULL, NULL, 13, 0, ADCx}, /* D31/PG13 */ + {GPIOG, NULL, NULL, 14, 0, ADCx}, /* D32/PG14 */ + {GPIOG, NULL, NULL, 8, 0, ADCx}, /* D33/PG8 */ + {GPIOG, NULL, NULL, 7, 0, ADCx}, /* D34/PG7 */ + {GPIOG, NULL, NULL, 6, 0, ADCx}, /* D35/PG6 */ + {GPIOB, NULL, NULL, 5, 0, ADCx}, /* D36/PB5 */ + {GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D37/PB6 */ + {GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* D38/PB7 */ + {GPIOF, NULL, ADC3, 6, 0, 4}, /* D39/PF6 */ + {GPIOF, NULL, ADC3, 7, 0, 5}, /* D40/PF7 */ + {GPIOF, NULL, ADC3, 8, 0, 6}, /* D41/PF8 */ + {GPIOF, NULL, ADC3, 9, 0, 7}, /* D42/PF9 */ + {GPIOF, NULL, ADC3, 10, 0, 8}, /* D43/PF10 */ + {GPIOF, NULL, NULL, 11, 0, ADCx}, /* D44/PF11 */ + {GPIOB, TIMER3, ADC1, 1, 4, 9}, /* D45/PB1 */ + {GPIOB, TIMER3, ADC1, 0, 3, 8}, /* D46/PB0 */ + {GPIOA, TIMER5, ADC1, 0, 1, 0}, /* D47/PA0 */ + {GPIOA, TIMER5, ADC1, 1, 2, 1}, /* D48/PA1 */ + {GPIOA, TIMER5, ADC1, 2, 3, 2}, /* D49/PA2 */ + {GPIOA, TIMER5, ADC1, 3, 4, 3}, /* D50/PA3 */ + {GPIOA, NULL, ADC1, 4, 0, 4}, /* D51/PA4 */ + {GPIOA, NULL, ADC1, 5, 0, 5}, /* D52/PA5 */ + {GPIOA, TIMER3, ADC1, 6, 1, 6}, /* D53/PA6 */ + {GPIOA, TIMER3, ADC1, 7, 2, 7}, /* D54/PA7 */ /* Right (triple) header */ - {GPIOF, NULL, 0, 0, ADCx}, /* D55/PF0 */ - {GPIOD, NULL, 11, 0, ADCx}, /* D56/PD11 */ - {GPIOD, NULL, 14, 0, ADCx}, /* D57/PD14 */ - {GPIOF, NULL, 1, 0, ADCx}, /* D58/PF1 */ - {GPIOD, NULL, 12, 0, ADCx}, /* D59/PD12 */ - {GPIOD, NULL, 15, 0, ADCx}, /* D60/PD15 */ - {GPIOF, NULL, 2, 0, ADCx}, /* D61/PF2 */ - {GPIOD, NULL, 13, 0, ADCx}, /* D62/PD13 */ - {GPIOD, NULL, 0, 0, ADCx}, /* D63/PD0 */ - {GPIOF, NULL, 3, 0, ADCx}, /* D64/PF3 */ - {GPIOE, NULL, 3, 0, ADCx}, /* D65/PE3 */ - {GPIOD, NULL, 1, 0, ADCx}, /* D66/PD1 */ - {GPIOF, NULL, 4, 0, ADCx}, /* D67/PF4 */ - {GPIOE, NULL, 4, 0, ADCx}, /* D68/PE4 */ - {GPIOE, NULL, 7, 0, ADCx}, /* D69/PE7 */ - {GPIOF, NULL, 5, 0, ADCx}, /* D70/PF5 */ - {GPIOE, NULL, 5, 0, ADCx}, /* D71/PE5 */ - {GPIOE, NULL, 8, 0, ADCx}, /* D72/PE8 */ - {GPIOF, NULL, 12, 0, ADCx}, /* D73/PF12 */ - {GPIOE, NULL, 6, 0, ADCx}, /* D74/PE6 */ - {GPIOE, NULL, 9, 0, ADCx}, /* D75/PE9 */ - {GPIOF, NULL, 13, 0, ADCx}, /* D76/PF13 */ - {GPIOE, NULL, 10, 0, ADCx}, /* D77/PE10 */ - {GPIOF, NULL, 14, 0, ADCx}, /* D78/PF14 */ - {GPIOG, NULL, 9, 0, ADCx}, /* D79/PG9 */ - {GPIOE, NULL, 11, 0, ADCx}, /* D80/PE11 */ - {GPIOF, NULL, 15, 0, ADCx}, /* D81/PF15 */ - {GPIOG, NULL, 10, 0, ADCx}, /* D82/PG10 */ - {GPIOE, NULL, 12, 0, ADCx}, /* D83/PE12 */ - {GPIOG, NULL, 0, 0, ADCx}, /* D84/PG0 */ - {GPIOD, NULL, 5, 0, ADCx}, /* D85/PD5 */ - {GPIOE, NULL, 13, 0, ADCx}, /* D86/PE13 */ - {GPIOG, NULL, 1, 0, ADCx}, /* D87/PG1 */ - {GPIOD, NULL, 4, 0, ADCx}, /* D88/PD4 */ - {GPIOE, NULL, 14, 0, ADCx}, /* D89/PE14 */ - {GPIOG, NULL, 2, 0, ADCx}, /* D90/PG2 */ - {GPIOE, NULL, 1, 0, ADCx}, /* D91/PE1 */ - {GPIOE, NULL, 15, 0, ADCx}, /* D92/PE15 */ - {GPIOG, NULL, 3, 0, ADCx}, /* D93/PG3 */ - {GPIOE, NULL, 0, 0, ADCx}, /* D94/PE0 */ - {GPIOD, NULL, 8, 0, ADCx}, /* D95/PD8 */ - {GPIOG, NULL, 4, 0, ADCx}, /* D96/PG4 */ - {GPIOD, NULL, 9, 0, ADCx}, /* D97/PD9 */ - {GPIOG, NULL, 5, 0, ADCx}, /* D98/PG5 */ - {GPIOD, NULL, 10, 0, ADCx} /* D99/PD10 */ + {GPIOF, NULL, NULL, 0, 0, ADCx}, /* D55/PF0 */ + {GPIOD, NULL, NULL, 11, 0, ADCx}, /* D56/PD11 */ + {GPIOD, NULL, NULL, 14, 0, ADCx}, /* D57/PD14 */ + {GPIOF, NULL, NULL, 1, 0, ADCx}, /* D58/PF1 */ + {GPIOD, NULL, NULL, 12, 0, ADCx}, /* D59/PD12 */ + {GPIOD, NULL, NULL, 15, 0, ADCx}, /* D60/PD15 */ + {GPIOF, NULL, NULL, 2, 0, ADCx}, /* D61/PF2 */ + {GPIOD, NULL, NULL, 13, 0, ADCx}, /* D62/PD13 */ + {GPIOD, NULL, NULL, 0, 0, ADCx}, /* D63/PD0 */ + {GPIOF, NULL, NULL, 3, 0, ADCx}, /* D64/PF3 */ + {GPIOE, NULL, NULL, 3, 0, ADCx}, /* D65/PE3 */ + {GPIOD, NULL, NULL, 1, 0, ADCx}, /* D66/PD1 */ + {GPIOF, NULL, NULL, 4, 0, ADCx}, /* D67/PF4 */ + {GPIOE, NULL, NULL, 4, 0, ADCx}, /* D68/PE4 */ + {GPIOE, NULL, NULL, 7, 0, ADCx}, /* D69/PE7 */ + {GPIOF, NULL, NULL, 5, 0, ADCx}, /* D70/PF5 */ + {GPIOE, NULL, NULL, 5, 0, ADCx}, /* D71/PE5 */ + {GPIOE, NULL, NULL, 8, 0, ADCx}, /* D72/PE8 */ + {GPIOF, NULL, NULL, 12, 0, ADCx}, /* D73/PF12 */ + {GPIOE, NULL, NULL, 6, 0, ADCx}, /* D74/PE6 */ + {GPIOE, NULL, NULL, 9, 0, ADCx}, /* D75/PE9 */ + {GPIOF, NULL, NULL, 13, 0, ADCx}, /* D76/PF13 */ + {GPIOE, NULL, NULL, 10, 0, ADCx}, /* D77/PE10 */ + {GPIOF, NULL, NULL, 14, 0, ADCx}, /* D78/PF14 */ + {GPIOG, NULL, NULL, 9, 0, ADCx}, /* D79/PG9 */ + {GPIOE, NULL, NULL, 11, 0, ADCx}, /* D80/PE11 */ + {GPIOF, NULL, NULL, 15, 0, ADCx}, /* D81/PF15 */ + {GPIOG, NULL, NULL, 10, 0, ADCx}, /* D82/PG10 */ + {GPIOE, NULL, NULL, 12, 0, ADCx}, /* D83/PE12 */ + {GPIOG, NULL, NULL, 0, 0, ADCx}, /* D84/PG0 */ + {GPIOD, NULL, NULL, 5, 0, ADCx}, /* D85/PD5 */ + {GPIOE, NULL, NULL, 13, 0, ADCx}, /* D86/PE13 */ + {GPIOG, NULL, NULL, 1, 0, ADCx}, /* D87/PG1 */ + {GPIOD, NULL, NULL, 4, 0, ADCx}, /* D88/PD4 */ + {GPIOE, NULL, NULL, 14, 0, ADCx}, /* D89/PE14 */ + {GPIOG, NULL, NULL, 2, 0, ADCx}, /* D90/PG2 */ + {GPIOE, NULL, NULL, 1, 0, ADCx}, /* D91/PE1 */ + {GPIOE, NULL, NULL, 15, 0, ADCx}, /* D92/PE15 */ + {GPIOG, NULL, NULL, 3, 0, ADCx}, /* D93/PG3 */ + {GPIOE, NULL, NULL, 0, 0, ADCx}, /* D94/PE0 */ + {GPIOD, NULL, NULL, 8, 0, ADCx}, /* D95/PD8 */ + {GPIOG, NULL, NULL, 4, 0, ADCx}, /* D96/PG4 */ + {GPIOD, NULL, NULL, 9, 0, ADCx}, /* D97/PD9 */ + {GPIOG, NULL, NULL, 5, 0, ADCx}, /* D98/PG5 */ + {GPIOD, NULL, NULL, 10, 0, ADCx} /* D99/PD10 */ }; #endif diff --git a/wirish/ext_interrupts.cpp b/wirish/ext_interrupts.cpp index 060994f..f9ccd39 100644 --- a/wirish/ext_interrupts.cpp +++ b/wirish/ext_interrupts.cpp @@ -49,7 +49,7 @@ void attachInterrupt(uint8 pin, voidFuncPtr handler, ExtIntTriggerMode mode) { exti_trigger_mode outMode = exti_out_mode(mode); - exti_attach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_pin), + exti_attach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_bit), gpio_exti_port(PIN_MAP[pin].gpio_device), handler, outMode); @@ -64,7 +64,7 @@ void detachInterrupt(uint8 pin) { return; } - exti_detach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_pin)); + exti_detach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_bit)); } static inline exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode) { diff --git a/wirish/io.h b/wirish/io.h index 8dad1d1..7d4fab1 100644 --- a/wirish/io.h +++ b/wirish/io.h @@ -28,8 +28,8 @@ * @brief Arduino-compatible digital pin I/O interface. */ -#ifndef _IO_H -#define _IO_H +#ifndef _IO_H_ +#define _IO_H_ #include "gpio.h" #include "adc.h" @@ -45,8 +45,8 @@ * This enum specifies the complete set of possible configurations; * not every pin can have all of these modes. For example, on the * Maple, pin 15 may be configured as INPUT_ANALOG, but not as PWM. - * See your device's silkscreen and and the GPIO documentation for - * more information. + * See your board's documentation and silkscreen for more information + * on what functionality is available on each pin. * * @see pinMode() */ @@ -114,8 +114,7 @@ typedef enum WiringPinMode { /** * Configure behavior of a GPIO pin. * - * @param pin Pin to configure. One of: 0-38 (pin numbers as labeled - * on silkscreen), or D0-D38 (symbols for same) + * @param pin Number of pin to configure. * @param mode Mode corresponding to desired pin behavior. * @see WiringPinMode */ @@ -136,8 +135,7 @@ void digitalWrite(uint8 pin, uint8 value); * Read a digital value from a pin. The pin must have its mode set to * one of INPUT, INPUT_PULLUP, and INPUT_PULLDOWN. * - * @param pin Pin to read from. One of: 0-38 (pin numbers as labeled - * on silkscreen), or D0-D38 (symbols for same) + * @param pin Pin to read from. * @return LOW or HIGH. * @see pinMode() */ @@ -146,18 +144,14 @@ uint32 digitalRead(uint8 pin); /** * Read an analog value from pin. This function blocks during ADC * conversion, and has 12 bits of resolution. The pin must have its - * mode set to INPUT_ANALOG. Ignoring function call overhead, - * conversion time is 55.5 cycles. + * mode set to INPUT_ANALOG. * - * @param pin Pin to read from. One of: 0, 1, 2, 3, 10, 11, 12, 13, - * 15, 16, 17, 18, 19, 20, 27, 28. - - * @return ADC-converted voltage, in the range 0--4095, inclusive - * (i.e. a 12-bit ADC conversion). - + * @param pin Pin to read from. + * @return Converted voltage, in the range 0--4095, (i.e. a 12-bit ADC + * conversion). * @see pinMode() */ -uint32 analogRead(uint8 pin); +uint16 analogRead(uint8 pin); /** * Toggles the digital value at the given pin. @@ -207,14 +201,15 @@ uint8 isButtonPressed(); * pinMode(BOARD_BUTTON_PIN, INPUT). * * @param timeout_millis Number of milliseconds to wait until the - * button is pressed. If timeout_millis is 0, wait forever. + * button is pressed. If timeout_millis is left out (or 0), wait + * forever. * * @return true, if the button was pressed; false, if the timeout was * reached. * * @see pinMode() */ -uint8 waitForButtonPress(uint32 timeout_millis); +uint8 waitForButtonPress(uint32 timeout_millis=0); /** * Shift out a byte of data, one bit at a time. diff --git a/wirish/pwm.cpp b/wirish/pwm.cpp index 6b09cef..4c803d2 100644 --- a/wirish/pwm.cpp +++ b/wirish/pwm.cpp @@ -38,5 +38,5 @@ void pwmWrite(uint8 pin, uint16 duty_cycle) { return; } - timer_set_compare(dev, PIN_MAP[pin].timer_chan, duty_cycle); + timer_set_compare(dev, PIN_MAP[pin].timer_channel, duty_cycle); } diff --git a/wirish/rules.mk b/wirish/rules.mk index c1d59bc..7715068 100644 --- a/wirish/rules.mk +++ b/wirish/rules.mk @@ -16,6 +16,7 @@ cSRCS_$(d) := cppSRCS_$(d) := wirish_math.cpp \ Print.cpp \ + boards.cpp \ boards/maple.cpp \ boards/maple_mini.cpp \ boards/maple_native.cpp \ @@ -24,14 +25,13 @@ cppSRCS_$(d) := wirish_math.cpp \ comm/HardwareSPI.cpp \ usb_serial.cpp \ cxxabi-compat.cpp \ - wirish.cpp \ wirish_shift.cpp \ wirish_analog.cpp \ time.cpp \ pwm.cpp \ ext_interrupts.cpp \ wirish_digital.cpp \ - native_sram.cpp \ + native_sram.cpp cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%) cppFILES_$(d) := $(cppSRCS_$(d):%=$(d)/%) diff --git a/wirish/wirish.h b/wirish/wirish.h index 13b14b6..880157d 100644 --- a/wirish/wirish.h +++ b/wirish/wirish.h @@ -67,7 +67,5 @@ typedef uint8 boolean; typedef uint8 byte; -void init(void); - #endif diff --git a/wirish/wirish_analog.cpp b/wirish/wirish_analog.cpp index 9e99aa5..8756caf 100644 --- a/wirish/wirish_analog.cpp +++ b/wirish/wirish_analog.cpp @@ -31,11 +31,12 @@ #include "io.h" /* Assumes that the ADC has been initialized and that the pin is set - * to ANALOG_INPUT */ -uint32 analogRead(uint8 pin) { - if(PIN_MAP[pin].adc_channel == ADCx) { + * to INPUT_ANALOG */ +uint16 analogRead(uint8 pin) { + const adc_dev *dev = PIN_MAP[pin].adc_device; + if (dev == NULL) { return 0; } - return adc_read(ADC1, PIN_MAP[pin].adc_channel); + return adc_read(dev, PIN_MAP[pin].adc_channel); } diff --git a/wirish/wirish_digital.cpp b/wirish/wirish_digital.cpp index 278cf10..115e91e 100644 --- a/wirish/wirish_digital.cpp +++ b/wirish/wirish_digital.cpp @@ -70,20 +70,14 @@ void pinMode(uint8 pin, WiringPinMode mode) { return; } - gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin, outputMode); + gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit, outputMode); if (PIN_MAP[pin].timer_device != NULL) { - /* enable/disable timer channels if we're switching into or - out of pwm */ - if (pwm) { - timer_set_mode(PIN_MAP[pin].timer_device, - PIN_MAP[pin].timer_chan, - TIMER_PWM); - } else { - timer_set_mode(PIN_MAP[pin].timer_device, - PIN_MAP[pin].timer_chan, - TIMER_DISABLED); - } + /* Enable/disable timer channels if we're switching into or + * out of PWM. */ + timer_set_mode(PIN_MAP[pin].timer_device, + PIN_MAP[pin].timer_channel, + pwm ? TIMER_PWM : TIMER_DISABLED); } } @@ -93,7 +87,7 @@ uint32 digitalRead(uint8 pin) { return 0; } - return gpio_read_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin) ? + return gpio_read_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit) ? HIGH : LOW; } @@ -102,7 +96,7 @@ void digitalWrite(uint8 pin, uint8 val) { return; } - gpio_write_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin, val); + gpio_write_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit, val); } void togglePin(uint8 pin) { @@ -110,12 +104,14 @@ void togglePin(uint8 pin) { return; } - gpio_toggle_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_pin); + gpio_toggle_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit); } +#define BUTTON_DEBOUNCE_DELAY 10 + uint8 isButtonPressed() { if (digitalRead(BOARD_BUTTON_PIN)) { - delay(1); + delay(BUTTON_DEBOUNCE_DELAY); while (digitalRead(BOARD_BUTTON_PIN)) ; return true; diff --git a/wirish/wirish_types.h b/wirish/wirish_types.h index 84591ea..7d6e31a 100644 --- a/wirish/wirish_types.h +++ b/wirish/wirish_types.h @@ -32,20 +32,28 @@ #include "gpio.h" #include "timer.h" +#include "adc.h" #ifndef _WIRISH_TYPES_H_ #define _WIRISH_TYPES_H_ -/** Stores STM32-specific information related to a given pin. */ +/** + * Invalid stm32_pin_info adc_channel value. + * @see stm32_pin_info + */ +#define ADCx 0xFF + +/** + * @brief Stores STM32-specific information related to a given Maple pin. + * @see PIN_MAP + */ typedef struct stm32_pin_info { - gpio_dev *gpio_device; /**< Maple pin's GPIO device */ - timer_dev *timer_device; /**< Maple pin's timer device, or NULL if none. */ - uint8 gpio_pin; /**< GPIO pin */ - uint8 timer_chan; /**< Timer channel, or 0 if none. */ - uint8 adc_channel; /**< Pin ADC channel, or ADCx if none. */ + gpio_dev *gpio_device; /**< Maple pin's GPIO device */ + timer_dev *timer_device; /**< Pin's timer device, if any. */ + const adc_dev *adc_device; /**< ADC device, if any. */ + uint8 gpio_bit; /**< Pin's GPIO port bit. */ + uint8 timer_channel; /**< Timer channel, or 0 if none. */ + uint8 adc_channel; /**< Pin ADC channel, or ADCx if none. */ } stm32_pin_info; -/** Invalid adc_channel value */ -#define ADCx 0xFF - #endif |