aboutsummaryrefslogtreecommitdiffstats
path: root/wirish
diff options
context:
space:
mode:
Diffstat (limited to 'wirish')
-rw-r--r--wirish/HardwareSPI.cpp (renamed from wirish/comm/HardwareSPI.cpp)22
-rw-r--r--wirish/HardwareSerial.cpp134
-rw-r--r--wirish/HardwareTimer.cpp65
-rw-r--r--wirish/Print.cpp6
-rw-r--r--wirish/boards.cpp178
-rw-r--r--wirish/boards/VLDiscovery/board.cpp (renamed from wirish/boards/maple.cpp)52
-rw-r--r--wirish/boards/VLDiscovery/include/board/board.h91
-rw-r--r--wirish/boards/maple/board.cpp143
-rw-r--r--wirish/boards/maple/include/board/board.h (renamed from wirish/boards/maple.h)29
-rw-r--r--wirish/boards/maple_RET6/board.cpp (renamed from wirish/boards/maple_RET6.cpp)13
-rw-r--r--wirish/boards/maple_RET6/include/board/board.h (renamed from wirish/boards/maple_RET6.h)12
-rw-r--r--wirish/boards/maple_mini/board.cpp (renamed from wirish/boards/maple_mini.cpp)15
-rw-r--r--wirish/boards/maple_mini/include/board/board.h (renamed from wirish/boards/maple_mini.h)7
-rw-r--r--wirish/boards/maple_native/board.cpp (renamed from wirish/boards/maple_native.cpp)18
-rw-r--r--wirish/boards/maple_native/include/board/board.h (renamed from wirish/boards/maple_native.h)7
-rw-r--r--wirish/boards/olimex_stm32_h103/board.cpp (renamed from wirish/boards/olimex_stm32_h103.cpp)15
-rw-r--r--wirish/boards/olimex_stm32_h103/include/board/board.h (renamed from wirish/boards/olimex_stm32_h103.h)4
-rw-r--r--wirish/boards/st_stm3220g_eval/board.cpp60
-rw-r--r--wirish/boards/st_stm3220g_eval/include/board/board.h53
-rw-r--r--wirish/boards_private.h71
-rw-r--r--wirish/comm/HardwareSerial.cpp119
-rw-r--r--wirish/ext_interrupts.cpp18
-rw-r--r--wirish/include/wirish/HardwareSPI.h (renamed from wirish/comm/HardwareSPI.h)21
-rw-r--r--wirish/include/wirish/HardwareSerial.h (renamed from wirish/comm/HardwareSerial.h)40
-rw-r--r--wirish/include/wirish/HardwareTimer.h (renamed from wirish/HardwareTimer.h)24
-rw-r--r--wirish/include/wirish/Print.h (renamed from wirish/Print.h)6
-rw-r--r--wirish/include/wirish/WProgram.h (renamed from wirish/WProgram.h)7
-rw-r--r--wirish/include/wirish/bit_constants.h (renamed from wirish/bit_constants.h)4
-rw-r--r--wirish/include/wirish/bits.h (renamed from wirish/bits.h)7
-rw-r--r--wirish/include/wirish/boards.h (renamed from wirish/boards.h)102
-rw-r--r--wirish/include/wirish/ext_interrupts.h (renamed from wirish/ext_interrupts.h)15
-rw-r--r--wirish/include/wirish/io.h (renamed from wirish/io.h)17
-rw-r--r--wirish/include/wirish/pwm.h (renamed from wirish/pwm.h)11
-rw-r--r--wirish/include/wirish/usb_serial.h (renamed from wirish/usb_serial.h)11
-rw-r--r--wirish/include/wirish/wirish.h (renamed from wirish/wirish.h)38
-rw-r--r--wirish/include/wirish/wirish_debug.h (renamed from wirish/wirish_debug.h)16
-rw-r--r--wirish/include/wirish/wirish_math.h (renamed from wirish/wirish_math.h)8
-rw-r--r--wirish/include/wirish/wirish_time.h (renamed from wirish/wirish_time.h)12
-rw-r--r--wirish/include/wirish/wirish_types.h (renamed from wirish/wirish_types.h)14
-rw-r--r--wirish/pwm.cpp21
-rw-r--r--wirish/rules.mk58
-rw-r--r--wirish/stm32f1/boards_setup.cpp89
-rw-r--r--wirish/stm32f1/util_hooks.c83
-rw-r--r--wirish/stm32f1/wirish_debug.cpp41
-rw-r--r--wirish/stm32f1/wirish_digital.cpp89
-rw-r--r--wirish/stm32f2/boards_setup.cpp120
-rw-r--r--wirish/stm32f2/util_hooks.c45
-rw-r--r--wirish/stm32f2/wirish_debug.cpp60
-rw-r--r--wirish/stm32f2/wirish_digital.cpp99
-rw-r--r--wirish/syscalls.c170
-rw-r--r--wirish/usb_serial.cpp18
-rw-r--r--wirish/wirish_analog.cpp17
-rw-r--r--wirish/wirish_digital.cpp70
-rw-r--r--wirish/wirish_math.cpp2
-rw-r--r--wirish/wirish_shift.cpp61
-rw-r--r--wirish/wirish_time.cpp6
56 files changed, 1906 insertions, 628 deletions
diff --git a/wirish/comm/HardwareSPI.cpp b/wirish/HardwareSPI.cpp
index 21ae180..120cd67 100644
--- a/wirish/comm/HardwareSPI.cpp
+++ b/wirish/HardwareSPI.cpp
@@ -29,14 +29,14 @@
* @brief Wirish SPI implementation.
*/
-#include "HardwareSPI.h"
+#include <wirish/HardwareSPI.h>
-#include "timer.h"
-#include "util.h"
-#include "rcc.h"
+#include <libmaple/timer.h>
+#include <libmaple/util.h>
+#include <libmaple/rcc.h>
-#include "wirish.h"
-#include "boards.h"
+#include <wirish/wirish.h>
+#include <wirish/boards.h>
struct spi_pins {
uint8 nss;
@@ -283,13 +283,9 @@ static void configure_gpios(spi_dev *dev, bool as_master) {
disable_pwm(misoi);
disable_pwm(mosii);
- spi_gpio_cfg(as_master,
- nssi->gpio_device,
- nssi->gpio_bit,
- scki->gpio_device,
- scki->gpio_bit,
- misoi->gpio_bit,
- mosii->gpio_bit);
+ spi_config_gpios(dev, as_master, nssi->gpio_device, nssi->gpio_bit,
+ scki->gpio_device, scki->gpio_bit, misoi->gpio_bit,
+ mosii->gpio_bit);
}
static const spi_baud_rate baud_rates[MAX_SPI_FREQS] __FLASH__ = {
diff --git a/wirish/HardwareSerial.cpp b/wirish/HardwareSerial.cpp
new file mode 100644
index 0000000..e78156d
--- /dev/null
+++ b/wirish/HardwareSerial.cpp
@@ -0,0 +1,134 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ *****************************************************************************/
+
+/**
+ * @file wirish/HardwareSerial.cpp
+ * @brief Wirish serial port implementation.
+ */
+
+#include <wirish/HardwareSerial.h>
+
+#include <libmaple/libmaple.h>
+#include <libmaple/gpio.h>
+#include <libmaple/timer.h>
+#include <libmaple/usart.h>
+
+#define DEFINE_HWSERIAL(name, n) \
+ HardwareSerial name(USART##n, \
+ BOARD_USART##n##_TX_PIN, \
+ BOARD_USART##n##_RX_PIN)
+
+#if BOARD_HAVE_USART1
+DEFINE_HWSERIAL(Serial1, 1);
+#endif
+#if BOARD_HAVE_USART2
+DEFINE_HWSERIAL(Serial2, 2);
+#endif
+#if BOARD_HAVE_USART3
+DEFINE_HWSERIAL(Serial3, 3);
+#endif
+#if BOARD_HAVE_UART4
+DEFINE_HWSERIAL(Serial4, 4);
+#endif
+#if BOARD_HAVE_UART5
+DEFINE_HWSERIAL(Serial5, 5);
+#endif
+#if BOARD_HAVE_USART6
+DEFINE_HWSERIAL(Serial6, 6);
+#endif
+
+HardwareSerial::HardwareSerial(usart_dev *usart_device,
+ uint8 tx_pin,
+ uint8 rx_pin) {
+ this->usart_device = usart_device;
+ this->tx_pin = tx_pin;
+ this->rx_pin = rx_pin;
+}
+
+/*
+ * Set up/tear down
+ */
+
+#if STM32_MCU_SERIES == STM32_SERIES_F1
+/* F1 MCUs have no GPIO_AFR[HL], so turn off PWM if there's a conflict
+ * on this GPIO bit. */
+static void disable_timer_if_necessary(timer_dev *dev, uint8 ch) {
+ if (dev != NULL) {
+ timer_set_mode(dev, ch, TIMER_DISABLED);
+ }
+}
+#elif (STM32_MCU_SERIES == STM32_SERIES_F2) || \
+ (STM32_MCU_SERIES == STM32_SERIES_F4)
+#define disable_timer_if_necessary(dev, ch) ((void)0)
+#else
+#warning "Unsupported STM32 series; timer conflicts are possible"
+#endif
+
+void HardwareSerial::begin(uint32 baud) {
+ ASSERT(baud <= this->usart_device->max_baud);
+
+ if (baud > this->usart_device->max_baud) {
+ return;
+ }
+
+ const stm32_pin_info *txi = &PIN_MAP[this->tx_pin];
+ const stm32_pin_info *rxi = &PIN_MAP[this->rx_pin];
+
+ disable_timer_if_necessary(txi->timer_device, txi->timer_channel);
+
+ usart_config_gpios_async(this->usart_device,
+ rxi->gpio_device, rxi->gpio_bit,
+ txi->gpio_device, txi->gpio_bit,
+ 0);
+ usart_init(this->usart_device);
+ usart_set_baud_rate(this->usart_device, USART_USE_PCLK, baud);
+ usart_enable(this->usart_device);
+}
+
+void HardwareSerial::end(void) {
+ usart_disable(this->usart_device);
+}
+
+/*
+ * I/O
+ */
+
+uint8 HardwareSerial::read(void) {
+ return usart_getc(this->usart_device);
+}
+
+uint32 HardwareSerial::available(void) {
+ return usart_data_available(this->usart_device);
+}
+
+void HardwareSerial::write(unsigned char ch) {
+ usart_putc(this->usart_device, ch);
+}
+
+void HardwareSerial::flush(void) {
+ usart_reset_rx(this->usart_device);
+}
diff --git a/wirish/HardwareTimer.cpp b/wirish/HardwareTimer.cpp
index bd61a89..4f68ad7 100644
--- a/wirish/HardwareTimer.cpp
+++ b/wirish/HardwareTimer.cpp
@@ -24,39 +24,47 @@
* SOFTWARE.
*****************************************************************************/
-#include "HardwareTimer.h"
-#include "boards.h" // for CYCLES_PER_MICROSECOND
-#include "wirish_math.h"
+#include <wirish/HardwareTimer.h>
+
+#include <libmaple/rcc.h>
+#include <wirish/ext_interrupts.h> // for noInterrupts(), interrupts()
+#include <wirish/wirish_math.h>
+#include <board/board.h> // for CYCLES_PER_MICROSECOND
// TODO [0.1.0] Remove deprecated pieces
-#ifdef STM32_MEDIUM_DENSITY
-#define NR_TIMERS 4
-#elif defined(STM32_HIGH_DENSITY)
-#define NR_TIMERS 8
-#else
-#error "Unsupported density"
-#endif
+/*
+ * Evil hack to infer this->dev from timerNum in the HardwareTimer
+ * constructor. See:
+ *
+ * http://www.parashift.com/c++-faq-lite/pointers-to-members.html#faq-33.2
+ * http://yosefk.com/c++fqa/function.html#fqa-33.2
+ */
+
+extern "C" {
+ static timer_dev **this_devp;
+ static rcc_clk_id this_id;
+ static void set_this_dev(timer_dev *dev) {
+ if (dev->clk_id == this_id) {
+ *this_devp = dev;
+ }
+ }
+}
-#define MAX_RELOAD ((1 << 16) - 1)
+/*
+ * HardwareTimer routines
+ */
HardwareTimer::HardwareTimer(uint8 timerNum) {
- if (timerNum > NR_TIMERS) {
- ASSERT(0);
- }
- timer_dev *devs[] = {
- TIMER1,
- TIMER2,
- TIMER3,
- TIMER4,
-#ifdef STM32_HIGH_DENSITY
- TIMER5,
- TIMER6,
- TIMER7,
- TIMER8,
-#endif
- };
- this->dev = devs[timerNum - 1];
+ rcc_clk_id timerID = (rcc_clk_id)(RCC_TIMER1 + (timerNum - 1));
+ this->dev = NULL;
+ noInterrupts(); // Hack to ensure we're the only ones using
+ // set_this_dev() and friends. TODO: use a lock.
+ this_id = timerID;
+ this_devp = &this->dev;
+ timer_foreach(set_this_dev);
+ interrupts();
+ ASSERT(this->dev != NULL);
}
void HardwareTimer::pause(void) {
@@ -92,6 +100,7 @@ void HardwareTimer::setCount(uint16 val) {
timer_set_count(this->dev, min(val, ovf));
}
+#define MAX_RELOAD ((1 << 16) - 1)
uint16 HardwareTimer::setPeriod(uint32 microseconds) {
// Not the best way to handle this edge case?
if (!microseconds) {
@@ -102,7 +111,7 @@ uint16 HardwareTimer::setPeriod(uint32 microseconds) {
uint32 period_cyc = microseconds * CYCLES_PER_MICROSECOND;
uint16 prescaler = (uint16)(period_cyc / MAX_RELOAD + 1);
- uint16 overflow = (uint16)round(period_cyc / prescaler);
+ uint16 overflow = (uint16)((period_cyc + (prescaler / 2)) / prescaler);
this->setPrescaleFactor(prescaler);
this->setOverflow(overflow);
return overflow;
diff --git a/wirish/Print.cpp b/wirish/Print.cpp
index 58c7cc7..f6bc0c6 100644
--- a/wirish/Print.cpp
+++ b/wirish/Print.cpp
@@ -1,6 +1,7 @@
/*
* Print.cpp - Base class that provides print() and println()
* Copyright (c) 2008 David A. Mellis. All right reserved.
+ * Copyright (c) 2011 LeafLabs, LLC.
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public License
@@ -21,8 +22,9 @@
* Modified 12 April 2011 by Marti Bolivar <mbolivar@leaflabs.com>
*/
-#include "Print.h"
+#include <wirish/Print.h>
+#include <wirish/wirish_math.h>
#include <limits.h>
#ifndef LLONG_MAX
@@ -40,8 +42,6 @@
#define LLONG_MAX 9223372036854775807LL
#endif
-#include "wirish_math.h"
-
/*
* Public methods
*/
diff --git a/wirish/boards.cpp b/wirish/boards.cpp
index 569ca6d..5771df5 100644
--- a/wirish/boards.cpp
+++ b/wirish/boards.cpp
@@ -2,6 +2,7 @@
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
@@ -25,45 +26,61 @@
*****************************************************************************/
/**
- * @brief Generic board initialization routines.
+ * @file wirish/boards.cpp
+ * @brief init() and board 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
- * at 72MHz. APB1 is clocked at 36MHz.
+ * This file is mostly interesting for the init() function, which
+ * configures Flash, the core clocks, and a variety of other available
+ * peripherals on the board so the rest of Wirish doesn't have to turn
+ * things on before using them.
+ *
+ * Prior to returning, init() calls boardInit(), which allows boards
+ * to perform any initialization they need to. This file includes a
+ * weak no-op definition of boardInit(), so boards that don't need any
+ * special initialization don't have to define their own.
+ *
+ * How init() works is chip-specific. See the boards_setup.cpp files
+ * under e.g. wirish/stm32f1/, wirish/stmf32f2 for the details, but be
+ * advised: their contents are unstable, and can/will change without
+ * notice.
*/
-#include "boards.h"
+#include <wirish/boards.h>
+#include <libmaple/libmaple_types.h>
+#include <libmaple/flash.h>
+#include <libmaple/nvic.h>
+#include <libmaple/systick.h>
+#include "boards_private.h"
-#include "flash.h"
-#include "rcc.h"
-#include "nvic.h"
-#include "systick.h"
-#include "gpio.h"
-#include "adc.h"
-#include "timer.h"
-#include "usb_cdcacm.h"
+static void setup_flash(void);
+static void setup_clocks(void);
+static void setup_nvic(void);
+static void setup_adcs(void);
+static void setup_timers(void);
-static void setupFlash(void);
-static void setupClocks(void);
-static void setupNVIC(void);
-static void setupADC(void);
-static void setupTimers(void);
+/*
+ * Exported functions
+ */
void init(void) {
- setupFlash();
- setupClocks();
- setupNVIC();
+ setup_flash();
+ setup_clocks();
+ setup_nvic();
systick_init(SYSTICK_RELOAD_VAL);
- gpio_init_all();
- afio_init();
- setupADC();
- setupTimers();
- usb_cdcacm_enable(BOARD_USB_DISC_DEV, BOARD_USB_DISC_BIT);
+ wirish::priv::board_setup_gpio();
+ setup_adcs();
+ setup_timers();
+ wirish::priv::board_setup_usb();
+ wirish::priv::series_init();
boardInit();
}
+/* Provide a default no-op boardInit(). */
+__weak void boardInit(void) {
+}
+
/* You could farm this out to the files in boards/ if e.g. it takes
- * too long to test on Maple Native (all those FSMC pins...). */
+ * too long to test on boards with lots of pins. */
bool boardUsesPin(uint8 pin) {
for (int i = 0; i < BOARD_NR_USED_PINS; i++) {
if (pin == boardUsedPins[i]) {
@@ -73,27 +90,56 @@ bool boardUsesPin(uint8 pin) {
return false;
}
-static void setupFlash(void) {
- flash_enable_prefetch();
- flash_set_latency(FLASH_WAIT_STATE_2);
-}
-
/*
- * Clock setup. Note that some of this only takes effect if we're
- * running bare metal and the bootloader hasn't done it for us
- * already.
- *
- * If you change this function, you MUST change the file-level Doxygen
- * comment above.
+ * Auxiliary routines
*/
-static void setupClocks() {
- rcc_clk_init(RCC_CLKSRC_PLL, RCC_PLLSRC_HSE, RCC_PLLMUL_9);
- rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1);
- rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2);
- rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1);
+
+static void setup_flash(void) {
+ // Turn on as many Flash "go faster" features as
+ // possible. flash_enable_features() just ignores any flags it
+ // can't support.
+ flash_enable_features(FLASH_PREFETCH | FLASH_ICACHE | FLASH_DCACHE);
+ // Configure the wait states, assuming we're operating at "close
+ // enough" to 3.3V.
+ flash_set_latency(FLASH_SAFE_WAIT_STATES);
+}
+
+static void setup_clocks(void) {
+ // Turn on HSI. We'll switch to and run off of this while we're
+ // setting up the main PLL.
+ rcc_turn_on_clk(RCC_CLK_HSI);
+
+ // Turn off and reset the clock subsystems we'll be using, as well
+ // as the clock security subsystem (CSS). Note that resetting CFGR
+ // to its default value of 0 implies a switch to HSI for SYSCLK.
+ RCC_BASE->CFGR = 0x00000000;
+ rcc_disable_css();
+ rcc_turn_off_clk(RCC_CLK_PLL);
+ rcc_turn_off_clk(RCC_CLK_HSE);
+ wirish::priv::board_reset_pll();
+ // Clear clock readiness interrupt flags and turn off clock
+ // readiness interrupts.
+ RCC_BASE->CIR = 0x00000000;
+
+ // Enable HSE, and wait until it's ready.
+ rcc_turn_on_clk(RCC_CLK_HSE);
+ while (!rcc_is_clk_ready(RCC_CLK_HSE))
+ ;
+
+ // Configure AHBx, APBx, etc. prescalers and the main PLL.
+ wirish::priv::board_setup_clock_prescalers();
+ rcc_configure_pll(&wirish::priv::w_board_pll_cfg);
+
+ // Enable the PLL, and wait until it's ready.
+ rcc_turn_on_clk(RCC_CLK_PLL);
+ while(!rcc_is_clk_ready(RCC_CLK_PLL))
+ ;
+
+ // Finally, switch to the now-ready PLL as the main clock source.
+ rcc_switch_sysclk(RCC_CLKSRC_PLL);
}
-static void setupNVIC() {
+static void setup_nvic(void) {
#ifdef VECT_TAB_FLASH
nvic_init(USER_ADDR_ROM, 0);
#elif defined VECT_TAB_RAM
@@ -105,31 +151,17 @@ static void setupNVIC() {
#endif
}
-static void adcDefaultConfig(const adc_dev* dev);
-
-static void setupADC() {
- rcc_set_prescaler(RCC_PRESCALER_ADC, RCC_ADCPRE_PCLK_DIV_6);
- adc_foreach(adcDefaultConfig);
+static void adc_default_config(const adc_dev *dev) {
+ adc_enable_single_swstart(dev);
+ adc_set_sample_rate(dev, wirish::priv::w_adc_smp);
}
-static void timerDefaultConfig(timer_dev*);
-
-static void setupTimers() {
- timer_foreach(timerDefaultConfig);
+static void setup_adcs(void) {
+ adc_set_prescaler(wirish::priv::w_adc_pre);
+ adc_foreach(adc_default_config);
}
-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) {
+static void timer_default_config(timer_dev *dev) {
timer_adv_reg_map *regs = (dev->regs).adv;
const uint16 full_overflow = 0xFFFF;
const uint16 half_duty = 0x8FFF;
@@ -142,22 +174,28 @@ static void timerDefaultConfig(timer_dev *dev) {
regs->SR = 0;
regs->DIER = 0;
regs->EGR = TIMER_EGR_UG;
-
switch (dev->type) {
case TIMER_ADVANCED:
regs->BDTR = TIMER_BDTR_MOE | TIMER_BDTR_LOCK_OFF;
// fall-through
case TIMER_GENERAL:
timer_set_reload(dev, full_overflow);
-
- for (int channel = 1; channel <= 4; channel++) {
- timer_set_compare(dev, channel, half_duty);
- timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1, TIMER_OC_PE);
+ for (uint8 channel = 1; channel <= 4; channel++) {
+ if (timer_has_cc_channel(dev, channel)) {
+ timer_set_compare(dev, channel, half_duty);
+ timer_oc_set_mode(dev, channel, TIMER_OC_MODE_PWM_1,
+ TIMER_OC_PE);
+ }
}
// fall-through
case TIMER_BASIC:
break;
}
+ timer_generate_update(dev);
timer_resume(dev);
}
+
+static void setup_timers(void) {
+ timer_foreach(timer_default_config);
+}
diff --git a/wirish/boards/maple.cpp b/wirish/boards/VLDiscovery/board.cpp
index 43d4386..c86204d 100644
--- a/wirish/boards/maple.cpp
+++ b/wirish/boards/VLDiscovery/board.cpp
@@ -25,29 +25,26 @@
*****************************************************************************/
/**
- * @file maple.cpp
- * @author Marti Bolivar <mbolivar@leaflabs.com>
- * @brief Maple PIN_MAP and boardInit().
+ * @file wirish/boards/VLDiscovery/board.cpp
+ * @author Anton Eltchaninov <anton.eltchaninov@gmail.com>
+ * @brief VLDiscovery board file.
*/
-#ifdef BOARD_maple
+#include <board/board.h>
-#include "maple.h"
-
-#include "gpio.h"
-#include "timer.h"
-#include "wirish_types.h"
+#include <libmaple/gpio.h>
+#include <libmaple/timer.h>
+#include <wirish/wirish_types.h>
void boardInit(void) {
+ afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY);
}
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = {
- /* 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, 0, 1, 0}, /* D2/PA0 (BUT) */
{GPIOA, TIMER2, ADC1, 1, 2, 1}, /* D3/PA1 */
{GPIOB, NULL, NULL, 5, 0, ADCx}, /* D4/PB5 */
{GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* D5/PB6 */
@@ -58,20 +55,14 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = {
{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) */
+ {GPIOA, NULL, ADC1, 5, 0, 5}, /* D13/PA5 */
{GPIOB, TIMER4, NULL, 8, 3, ADCx}, /* D14/PB8 */
-
- /* Little header */
-
{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, NULL, 13, 0, ADCx}, /* D21/PC13 */
{GPIOC, NULL, NULL, 14, 0, ADCx}, /* D22/PC14 */
{GPIOC, NULL, NULL, 15, 0, ADCx}, /* D23/PC15 */
@@ -88,16 +79,16 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = {
{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) */
-
- /* JTAG header */
-
- {GPIOA, NULL, NULL, 13, 0, ADCx}, /* D39/PA13 */
- {GPIOA, NULL, NULL, 14, 0, ADCx}, /* D40/PA14 */
+ {GPIOC, NULL, NULL, 8, 0, ADCx}, /* D37/PC8 (Blue led) */
+ {GPIOC, NULL, NULL, 9, 0, ADCx}, /* D38/PC9 (Green led) */
+ {GPIOA, TIMER1, NULL, 11, 4, ADCx}, /* D39/PA11 */
+ {GPIOA, NULL, NULL, 12, 0, ADCx}, /* D40/PA12 */
{GPIOA, NULL, NULL, 15, 0, ADCx}, /* D41/PA15 */
- {GPIOB, NULL, NULL, 3, 0, ADCx}, /* D42/PB3 */
- {GPIOB, NULL, NULL, 4, 0, ADCx}, /* D43/PB4 */
+ {GPIOB, NULL, NULL, 2, 0, ADCx}, /* D42/PB2 */
+ {GPIOB, NULL, NULL, 3, 0, ADCx}, /* D43/PB3 */
+ {GPIOB, NULL, NULL, 4, 0, ADCx}, /* D44/PB4 */
+ {GPIOC, NULL, NULL, 11, 0, ADCx}, /* D45/PC11 */
+ {GPIOC, NULL, NULL, 12, 0, ADCx} /* D46/PC12 */
};
extern const uint8 boardPWMPins[] __FLASH__ = {
@@ -109,8 +100,5 @@ extern const uint8 boardADCPins[] __FLASH__ = {
};
extern const uint8 boardUsedPins[] __FLASH__ = {
- BOARD_LED_PIN, BOARD_BUTTON_PIN, BOARD_JTMS_SWDIO_PIN,
- BOARD_JTCK_SWCLK_PIN, BOARD_JTDI_PIN, BOARD_JTDO_PIN, BOARD_NJTRST_PIN
+ BOARD_BLUE_LED_PIN, BOARD_GREEN_LED_PIN, BOARD_BUTTON_PIN
};
-
-#endif
diff --git a/wirish/boards/VLDiscovery/include/board/board.h b/wirish/boards/VLDiscovery/include/board/board.h
new file mode 100644
index 0000000..04d21c7
--- /dev/null
+++ b/wirish/boards/VLDiscovery/include/board/board.h
@@ -0,0 +1,91 @@
+/******************************************************************************
+ * 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 wirish/boards/VLDiscovery/include/board/board.h
+ * @author Anton Eltchaninov <anton.eltchaninov@gmail.com>
+ * @brief VLDiscovery board header.
+ */
+
+#ifndef _BOARD_VLDISCOVERY_H_
+#define _BOARD_VLDISCOVERY_H_
+
+#define BOARD_RCC_PLLMUL RCC_PLLMUL_3
+
+#define CYCLES_PER_MICROSECOND 24
+#define SYSTICK_RELOAD_VAL 23999 /* takes a cycle to reload */
+
+#define BOARD_BUTTON_PIN 2 /* PA0 USER */
+#define BOARD_BLUE_LED_PIN 37 /* blue led LD4 */
+#define BOARD_GREEN_LED_PIN 38 /* green led LD3 */
+#define BOARD_LED_PIN BOARD_BLUE_LED_PIN
+
+/* Number of USARTs/UARTs whose pins are broken out to headers */
+#define BOARD_NR_USARTS 3
+
+/* Default USART pin numbers (not considering AFIO remap) */
+#define BOARD_USART1_TX_PIN 7
+#define BOARD_USART1_RX_PIN 8
+#define BOARD_USART2_TX_PIN 1
+#define BOARD_USART2_RX_PIN 0
+#define BOARD_USART3_TX_PIN 29
+#define BOARD_USART3_RX_PIN 30
+
+/* Number of SPI ports */
+#define BOARD_NR_SPI 2
+
+/* Default SPI pin numbers (not considering AFIO remap) */
+#define BOARD_SPI1_NSS_PIN 10
+#define BOARD_SPI1_MOSI_PIN 11
+#define BOARD_SPI1_MISO_PIN 12
+#define BOARD_SPI1_SCK_PIN 13
+#define BOARD_SPI2_NSS_PIN 31
+#define BOARD_SPI2_MOSI_PIN 34
+#define BOARD_SPI2_MISO_PIN 33
+#define BOARD_SPI2_SCK_PIN 32
+
+/* Total number of GPIO pins that are broken out to headers and
+ * intended for general use. */
+#define BOARD_NR_GPIO_PINS 47
+
+/* Number of pins capable of PWM output */
+#define BOARD_NR_PWM_PINS 15
+
+/* Number of pins capable of ADC conversion */
+#define BOARD_NR_ADC_PINS 15
+
+/* Number of pins already connected to external hardware. */
+#define BOARD_NR_USED_PINS 3
+
+/* Save Maple pin order and define aliases */
+enum {
+PA3, PA2, PA0, PA1, PB5, PB6, PA8, PA9, PA10, PB7, PA4, PA7, PA6, PA5,
+PB8, PC0, PC1, PC2, PC3, PC4, PC5, PC13, PC14, PC15, PB9, PD2, PC10,
+PB0, PB1, PB10, PB11, PB12, PB13, PB14, PB15, PC6, PC7, PC8, PC9,
+PA11, PA12, PA15, PB2, PB3, PB4, PC11, PC12 };
+
+
+#endif
diff --git a/wirish/boards/maple/board.cpp b/wirish/boards/maple/board.cpp
new file mode 100644
index 0000000..a585ea1
--- /dev/null
+++ b/wirish/boards/maple/board.cpp
@@ -0,0 +1,143 @@
+/******************************************************************************
+ * 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 wirish/boards/maple/board.cpp
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief Maple board file.
+ */
+
+#include <board/board.h> // For this board's header file
+
+#include <wirish/wirish_types.h> // For stm32_pin_info and its contents
+ // (these go into PIN_MAP).
+
+#include "boards_private.h" // For PMAP_ROW(), which makes
+ // PIN_MAP easier to read.
+
+// boardInit(): nothing special to do for Maple.
+//
+// When defining your own board.cpp, you can put extra code in this
+// function if you have anything you want done on reset, before main()
+// or setup() are called.
+//
+// If there's nothing special you need done, feel free to leave this
+// function out, as we do here.
+/*
+void boardInit(void) {
+}
+*/
+
+// Pin map: this lets the basic I/O functions (digitalWrite(),
+// analogRead(), pwmWrite()) translate from pin numbers to STM32
+// peripherals.
+//
+// PMAP_ROW() lets us specify a row (really a struct stm32_pin_info)
+// in the pin map. Its arguments are:
+//
+// - GPIO device for the pin (GPIOA, etc.)
+// - GPIO bit for the pin (0 through 15)
+// - Timer device, or NULL if none
+// - Timer channel (1 to 4, for PWM), or 0 if none
+// - ADC device, or NULL if none
+// - ADC channel, or ADCx if none
+extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = {
+
+ /* Top header */
+
+ PMAP_ROW(GPIOA, 3, TIMER2, 4, ADC1, 3), /* D0/PA3 */
+ PMAP_ROW(GPIOA, 2, TIMER2, 3, ADC1, 2), /* D1/PA2 */
+ PMAP_ROW(GPIOA, 0, TIMER2, 1, ADC1, 0), /* D2/PA0 */
+ PMAP_ROW(GPIOA, 1, TIMER2, 2, ADC1, 1), /* D3/PA1 */
+ PMAP_ROW(GPIOB, 5, NULL, 0, NULL, ADCx), /* D4/PB5 */
+ PMAP_ROW(GPIOB, 6, TIMER4, 1, NULL, ADCx), /* D5/PB6 */
+ PMAP_ROW(GPIOA, 8, TIMER1, 1, NULL, ADCx), /* D6/PA8 */
+ PMAP_ROW(GPIOA, 9, TIMER1, 2, NULL, ADCx), /* D7/PA9 */
+ PMAP_ROW(GPIOA, 10, TIMER1, 3, NULL, ADCx), /* D8/PA10 */
+ PMAP_ROW(GPIOB, 7, TIMER4, 2, NULL, ADCx), /* D9/PB7 */
+ PMAP_ROW(GPIOA, 4, NULL, 0, ADC1, 4), /* D10/PA4 */
+ PMAP_ROW(GPIOA, 7, TIMER3, 2, ADC1, 7), /* D11/PA7 */
+ PMAP_ROW(GPIOA, 6, TIMER3, 1, ADC1, 6), /* D12/PA6 */
+ PMAP_ROW(GPIOA, 5, NULL, 0, ADC1, 5), /* D13/PA5 (LED) */
+ PMAP_ROW(GPIOB, 8, TIMER4, 3, NULL, ADCx), /* D14/PB8 */
+
+ /* Little header */
+
+ PMAP_ROW(GPIOC, 0, NULL, 0, ADC1, 10), /* D15/PC0 */
+ PMAP_ROW(GPIOC, 1, NULL, 0, ADC1, 11), /* D16/PC1 */
+ PMAP_ROW(GPIOC, 2, NULL, 0, ADC1, 12), /* D17/PC2 */
+ PMAP_ROW(GPIOC, 3, NULL, 0, ADC1, 13), /* D18/PC3 */
+ PMAP_ROW(GPIOC, 4, NULL, 0, ADC1, 14), /* D19/PC4 */
+ PMAP_ROW(GPIOC, 5, NULL, 0, ADC1, 15), /* D20/PC5 */
+
+ /* External header */
+
+ PMAP_ROW(GPIOC, 13, NULL, 0, NULL, ADCx), /* D21/PC13 */
+ PMAP_ROW(GPIOC, 14, NULL, 0, NULL, ADCx), /* D22/PC14 */
+ PMAP_ROW(GPIOC, 15, NULL, 0, NULL, ADCx), /* D23/PC15 */
+ PMAP_ROW(GPIOB, 9, TIMER4, 4, NULL, ADCx), /* D24/PB9 */
+ PMAP_ROW(GPIOD, 2, NULL, 0, NULL, ADCx), /* D25/PD2 */
+ PMAP_ROW(GPIOC, 10, NULL, 0, NULL, ADCx), /* D26/PC10 */
+ PMAP_ROW(GPIOB, 0, TIMER3, 3, ADC1, 8), /* D27/PB0 */
+ PMAP_ROW(GPIOB, 1, TIMER3, 4, ADC1, 9), /* D28/PB1 */
+ PMAP_ROW(GPIOB, 10, NULL, 0, NULL, ADCx), /* D29/PB10 */
+ PMAP_ROW(GPIOB, 11, NULL, 0, NULL, ADCx), /* D30/PB11 */
+ PMAP_ROW(GPIOB, 12, NULL, 0, NULL, ADCx), /* D31/PB12 */
+ PMAP_ROW(GPIOB, 13, NULL, 0, NULL, ADCx), /* D32/PB13 */
+ PMAP_ROW(GPIOB, 14, NULL, 0, NULL, ADCx), /* D33/PB14 */
+ PMAP_ROW(GPIOB, 15, NULL, 0, NULL, ADCx), /* D34/PB15 */
+ PMAP_ROW(GPIOC, 6, NULL, 0, NULL, ADCx), /* D35/PC6 */
+ PMAP_ROW(GPIOC, 7, NULL, 0, NULL, ADCx), /* D36/PC7 */
+ PMAP_ROW(GPIOC, 8, NULL, 0, NULL, ADCx), /* D37/PC8 */
+ PMAP_ROW(GPIOC, 9, NULL, 0, NULL, ADCx), /* D38/PC9 (BUT) */
+
+ /* JTAG header */
+
+ PMAP_ROW(GPIOA, 13, NULL, 0, NULL, ADCx), /* D39/PA13 */
+ PMAP_ROW(GPIOA, 14, NULL, 0, NULL, ADCx), /* D40/PA14 */
+ PMAP_ROW(GPIOA, 15, NULL, 0, NULL, ADCx), /* D41/PA15 */
+ PMAP_ROW(GPIOB, 3, NULL, 0, NULL, ADCx), /* D42/PB3 */
+ PMAP_ROW(GPIOB, 4, NULL, 0, NULL, ADCx), /* D43/PB4 */
+};
+
+// Array of pins you can use for pwmWrite(). Keep it in Flash because
+// it doesn't change, and so we don't waste RAM.
+extern const uint8 boardPWMPins[] __FLASH__ = {
+ 0, 1, 2, 3, 5, 6, 7, 8, 9, 11, 12, 14, 24, 27, 28
+};
+
+// Array of pins you can use for analogRead().
+extern const uint8 boardADCPins[] __FLASH__ = {
+ 0, 1, 2, 3, 10, 11, 12, 15, 16, 17, 18, 19, 20, 27, 28
+};
+
+// Array of pins that the board uses for something special. Other than
+// the button and the LED, it's usually best to leave these pins alone
+// unless you know what you're doing.
+extern const uint8 boardUsedPins[] __FLASH__ = {
+ BOARD_LED_PIN, BOARD_BUTTON_PIN, BOARD_JTMS_SWDIO_PIN,
+ BOARD_JTCK_SWCLK_PIN, BOARD_JTDI_PIN, BOARD_JTDO_PIN, BOARD_NJTRST_PIN
+};
diff --git a/wirish/boards/maple.h b/wirish/boards/maple/include/board/board.h
index a986884..72a4282 100644
--- a/wirish/boards/maple.h
+++ b/wirish/boards/maple/include/board/board.h
@@ -25,24 +25,27 @@
*****************************************************************************/
/**
- * @file maple.h
+ * @file wirish/boards/maple/include/board/board.h
* @author Marti Bolivar <mbolivar@leaflabs.com>
- * @brief Private include file for Maple in boards.h
+ * @brief Maple board header.
*/
#ifndef _BOARD_MAPLE_H_
#define _BOARD_MAPLE_H_
+/* 72 MHz -> 72 cycles per microsecond. */
#define CYCLES_PER_MICROSECOND 72
-#define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */
+/* Pin number for the built-in button. */
#define BOARD_BUTTON_PIN 38
+
+/* Pin number for the built-in LED. */
#define BOARD_LED_PIN 13
-/* Number of USARTs/UARTs whose pins are broken out to headers */
+/* Number of USARTs/UARTs whose pins are broken out to headers. */
#define BOARD_NR_USARTS 3
-/* Default USART pin numbers (not considering AFIO remap) */
+/* USART pin numbers. */
#define BOARD_USART1_TX_PIN 7
#define BOARD_USART1_RX_PIN 8
#define BOARD_USART2_TX_PIN 1
@@ -50,10 +53,10 @@
#define BOARD_USART3_TX_PIN 29
#define BOARD_USART3_RX_PIN 30
-/* Number of SPI ports */
+/* Number of SPI ports broken out to headers. */
#define BOARD_NR_SPI 2
-/* Default SPI pin numbers (not considering AFIO remap) */
+/* SPI pin numbers. */
#define BOARD_SPI1_NSS_PIN 10
#define BOARD_SPI1_MOSI_PIN 11
#define BOARD_SPI1_MISO_PIN 12
@@ -64,20 +67,22 @@
#define BOARD_SPI2_SCK_PIN 32
/* Total number of GPIO pins that are broken out to headers and
- * intended for general use. */
+ * intended for use. This includes pins like the LED, button, and
+ * debug port (JTAG/SWD) pins. */
#define BOARD_NR_GPIO_PINS 44
-/* Number of pins capable of PWM output */
+/* Number of pins capable of PWM output. */
#define BOARD_NR_PWM_PINS 15
-/* Number of pins capable of ADC conversion */
+/* Number of pins capable of ADC conversion. */
#define BOARD_NR_ADC_PINS 15
/* Number of pins already connected to external hardware. For Maple,
- * these are just BOARD_LED_PIN and BOARD_BUTTON_PIN. */
+ * these are just BOARD_LED_PIN, BOARD_BUTTON_PIN, and the debug port
+ * pins (see below). */
#define BOARD_NR_USED_PINS 7
-/* Debug port pins */
+/* Debug port pins. */
#define BOARD_JTMS_SWDIO_PIN 39
#define BOARD_JTCK_SWCLK_PIN 40
#define BOARD_JTDI_PIN 41
diff --git a/wirish/boards/maple_RET6.cpp b/wirish/boards/maple_RET6/board.cpp
index cbd7e25..2ef7de7 100644
--- a/wirish/boards/maple_RET6.cpp
+++ b/wirish/boards/maple_RET6/board.cpp
@@ -25,18 +25,17 @@
*****************************************************************************/
/**
- * @file maple_RET6.cpp
+ * @file wirish/boards/maple_RET6/board.cpp
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief Maple RET6 Edition board file
*/
-#ifdef BOARD_maple_RET6
+#include <board/board.h>
-#include "maple_RET6.h"
+#include <libmaple/gpio.h>
+#include <libmaple/timer.h>
-#include "gpio.h"
-#include "timer.h"
-#include "wirish_types.h"
+#include <wirish/wirish_types.h>
void boardInit(void) {
}
@@ -114,5 +113,3 @@ extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = {
BOARD_LED_PIN, BOARD_BUTTON_PIN, BOARD_JTMS_SWDIO_PIN,
BOARD_JTCK_SWCLK_PIN, BOARD_JTDI_PIN, BOARD_JTDO_PIN, BOARD_NJTRST_PIN
};
-
-#endif
diff --git a/wirish/boards/maple_RET6.h b/wirish/boards/maple_RET6/include/board/board.h
index 9e7ce9d..05b9031 100644
--- a/wirish/boards/maple_RET6.h
+++ b/wirish/boards/maple_RET6/include/board/board.h
@@ -25,26 +25,24 @@
*****************************************************************************/
/**
- * @file maple_RET6.h
+ * @file wirish/boards/maple_RET6/include/board/board.h
* @author Marti Bolivar <mbolivar@leaflabs.com>
- * @brief Private include file for Maple RET6 Edition in boards.h
+ * @brief Maple RET6 Edition board header.
*
- * See maple.h for more information on these definitions.
+ * See wirish/boards/maple/include/board/board.h for more information
+ * on these definitions.
*/
#ifndef _BOARDS_MAPLE_RET6_H_
#define _BOARDS_MAPLE_RET6_H_
-/* A few of these values will seem strange given that it's a
- * high-density board. */
-
#define CYCLES_PER_MICROSECOND 72
#define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */
#define BOARD_BUTTON_PIN 38
#define BOARD_LED_PIN 13
-/* Note: UART4 and UART5 have pins which aren't broken out :( */
+/* UART4 and UART5 have pins which aren't broken out :( */
#define BOARD_NR_USARTS 3
#define BOARD_USART1_TX_PIN 7
#define BOARD_USART1_RX_PIN 8
diff --git a/wirish/boards/maple_mini.cpp b/wirish/boards/maple_mini/board.cpp
index f111a14..599cb66 100644
--- a/wirish/boards/maple_mini.cpp
+++ b/wirish/boards/maple_mini/board.cpp
@@ -25,19 +25,18 @@
*****************************************************************************/
/**
- * @file maple_mini.cpp
+ * @file wirish/boards/maple_mini/board.cpp
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief Maple Mini board file.
*/
-#ifdef BOARD_maple_mini
+#include <board/board.h>
-#include "maple_mini.h"
+#include <libmaple/gpio.h>
+#include <libmaple/timer.h>
-#include "gpio.h"
-#include "timer.h"
-#include "wirish_debug.h"
-#include "wirish_types.h"
+#include <wirish/wirish_debug.h>
+#include <wirish/wirish_types.h>
/* Since we want the Serial Wire/JTAG pins as GPIOs, disable both SW
* and JTAG debug support */
@@ -102,5 +101,3 @@ extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = {
extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = {
BOARD_LED_PIN, BOARD_BUTTON_PIN, USB_DP, USB_DM
};
-
-#endif
diff --git a/wirish/boards/maple_mini.h b/wirish/boards/maple_mini/include/board/board.h
index 40f507b..bfba46d 100644
--- a/wirish/boards/maple_mini.h
+++ b/wirish/boards/maple_mini/include/board/board.h
@@ -25,11 +25,12 @@
*****************************************************************************/
/**
- * @file maple_mini.h
+ * @file wirish/boards/maple_mini/include/board/board.h
* @author Marti Bolivar <mbolivar@leaflabs.com>
- * @brief Private include file for Maple Mini in boards.h
+ * @brief Maple Mini board header.
*
- * See maple.h for more information on these definitions.
+ * See wirish/boards/maple/include/board/board.h for more information
+ * on these definitions.
*/
#ifndef _BOARD_MAPLE_MINI_H_
diff --git a/wirish/boards/maple_native.cpp b/wirish/boards/maple_native/board.cpp
index 821be77..515cf5b 100644
--- a/wirish/boards/maple_native.cpp
+++ b/wirish/boards/maple_native/board.cpp
@@ -25,21 +25,19 @@
*****************************************************************************/
/**
- * @file maple_native.cpp
+ * @file wirish/boards/maple_native/board.cpp
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief Maple Native board file.
*/
-#ifdef BOARD_maple_native
+#include <board/board.h>
-#include "maple_native.h"
+#include <libmaple/fsmc.h>
+#include <libmaple/gpio.h>
+#include <libmaple/rcc.h>
+#include <libmaple/timer.h>
-#include "fsmc.h"
-#include "gpio.h"
-#include "rcc.h"
-#include "timer.h"
-
-#include "wirish_types.h"
+#include <wirish/wirish_types.h>
static void initSRAMChip(void);
@@ -197,5 +195,3 @@ static void initSRAMChip(void) {
fsmc_nor_psram_set_addset(regs, 0);
fsmc_nor_psram_set_datast(regs, 3);
}
-
-#endif
diff --git a/wirish/boards/maple_native.h b/wirish/boards/maple_native/include/board/board.h
index 7c09014..397afaf 100644
--- a/wirish/boards/maple_native.h
+++ b/wirish/boards/maple_native/include/board/board.h
@@ -25,11 +25,12 @@
*****************************************************************************/
/**
- * @file maple_native.h
+ * @file wirish/boards/maple_native/include/board/board.h.
* @author Marti Bolivar <mbolivar@leaflabs.com>
- * @brief Private include file for Maple Native in boards.h
+ * @brief Maple Native board header file.
*
- * See maple.h for more information on these definitions.
+ * See wirish/boards/maple/include/board/board.h for more information
+ * on these definitions.
*/
#ifndef _BOARD_MAPLE_NATIVE_H_
diff --git a/wirish/boards/olimex_stm32_h103.cpp b/wirish/boards/olimex_stm32_h103/board.cpp
index a9f0936..d9b8033 100644
--- a/wirish/boards/olimex_stm32_h103.cpp
+++ b/wirish/boards/olimex_stm32_h103/board.cpp
@@ -26,18 +26,17 @@
*****************************************************************************/
/**
- * @file olimex_stm32_h103.cpp
+ * @file wirish/boards/olimex_stm32_h103/board.cpp
* @author David Kiliani <mail@davidkiliani.de>
- * @brief Olimex STM32_H103 PIN_MAP and boardInit().
+ * @brief Olimex STM32_H103 board file.
*/
-#ifdef BOARD_olimex_stm32_h103
+#include <board/board.h>
-#include "olimex_stm32_h103.h"
+#include <libmaple/gpio.h>
+#include <libmaple/timer.h>
-#include "gpio.h"
-#include "timer.h"
-#include "wirish_types.h"
+#include <wirish/wirish_types.h>
void boardInit(void) {
}
@@ -118,5 +117,3 @@ extern const uint8 boardUsedPins[] __FLASH__ = {
BOARD_LED_PIN, BOARD_BUTTON_PIN, BOARD_JTMS_SWDIO_PIN,
BOARD_JTCK_SWCLK_PIN, BOARD_JTDI_PIN, BOARD_JTDO_PIN, BOARD_NJTRST_PIN
};
-
-#endif
diff --git a/wirish/boards/olimex_stm32_h103.h b/wirish/boards/olimex_stm32_h103/include/board/board.h
index d2b5fcc..b312e26 100644
--- a/wirish/boards/olimex_stm32_h103.h
+++ b/wirish/boards/olimex_stm32_h103/include/board/board.h
@@ -26,9 +26,9 @@
*****************************************************************************/
/**
- * @file olimex_stm32_h103.h
+ * @file wirish/boards/olimex_stm32_h103/include/board/board.h
* @author David Kiliani <mail@davidkiliani.de>
- * @brief Private include file for Olimex STM32_H103 in boards.h
+ * @brief Olimex STM32_H103 board header.
*/
#ifndef _BOARD_OLIMEX_STM32_H103_H_
diff --git a/wirish/boards/st_stm3220g_eval/board.cpp b/wirish/boards/st_stm3220g_eval/board.cpp
new file mode 100644
index 0000000..674fc67
--- /dev/null
+++ b/wirish/boards/st_stm3220g_eval/board.cpp
@@ -0,0 +1,60 @@
+/******************************************************************************
+ * 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 wirish/boards/st_stm3220g_eval/board.cpp
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief STM3220G-EVAL board file.
+ */
+
+#include <board/board.h>
+
+#include <libmaple/gpio.h>
+#include <libmaple/timer.h>
+#include <wirish/wirish_types.h>
+
+/* Board initialization. Unused. */
+void boardInit(void) {
+}
+
+/* Pin map. Current restrictions:
+ * - LEDs and user button only
+ * - GPIO devices only (no timers etc. yet)
+ */
+#define pmap_row(dev, bit) {dev, NULL, NULL, bit, 0, ADCx}
+extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = {
+ pmap_row(GPIOG, 6), /* D0/PG6 (LED1) */
+ pmap_row(GPIOG, 8), /* D1/PG8 (LED2) */
+ pmap_row(GPIOI, 9), /* D2/PI9 (LED3) */
+ pmap_row(GPIOC, 7), /* D4/PC7 (LED4) */
+ pmap_row(GPIOG, 15), /* D5/PG15 (BUT) */
+};
+#undef pmap_row
+
+/* Special pin arrays. Unused. */
+extern const uint8 boardPWMPins[] __FLASH__ = {};
+extern const uint8 boardADCPins[] __FLASH__ = {};
+extern const uint8 boardUsedPins[] __FLASH__ = {};
diff --git a/wirish/boards/st_stm3220g_eval/include/board/board.h b/wirish/boards/st_stm3220g_eval/include/board/board.h
new file mode 100644
index 0000000..fe9658a
--- /dev/null
+++ b/wirish/boards/st_stm3220g_eval/include/board/board.h
@@ -0,0 +1,53 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ *****************************************************************************/
+
+/**
+ * @file wirish/boards/st_stm3220g_eval/include/board/board.h
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief STM3220G-EVAL board stub header.
+ *
+ * This (and the corresponding board.cpp) needs to be fixed and
+ * fleshed out. Do it later? Maybe someone who wants support for this
+ * board will do it.
+ */
+
+#ifndef _BOARD_ST_STM3220G_EVAL_H_
+#define _BOARD_ST_STM3220G_EVAL_H_
+
+#define CYCLES_PER_MICROSECOND 120
+#define SYSTICK_RELOAD_VAL 119999 /* takes a cycle to reload */
+
+#define BOARD_BUTTON_PIN 5
+#define BOARD_LED_PIN 0
+
+#define BOARD_NR_USARTS 0
+#define BOARD_NR_SPI 0
+#define BOARD_NR_GPIO_PINS 6
+#define BOARD_NR_PWM_PINS 0
+#define BOARD_NR_ADC_PINS 0
+#define BOARD_NR_USED_PINS 6
+
+#endif
diff --git a/wirish/boards_private.h b/wirish/boards_private.h
new file mode 100644
index 0000000..49867ca
--- /dev/null
+++ b/wirish/boards_private.h
@@ -0,0 +1,71 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ *****************************************************************************/
+
+/**
+ * @file wirish/boards_private.h
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief Private board support header.
+ *
+ * This file declares chip-specific variables and functions which
+ * determine how init() behaves. It is not part of the public Wirish
+ * API, and can change without notice.
+ */
+
+#ifndef _WIRISH_BOARDS_PRIVATE_H_
+#define _WIRISH_BOARDS_PRIVATE_H_
+
+#include <libmaple/rcc.h>
+#include <libmaple/adc.h>
+
+/* Makes the PIN_MAP rows more human-readable. */
+#define PMAP_ROW(gpio_dev, gpio_bit, timer_dev, timer_ch, adc_dev, adc_ch) \
+ { gpio_dev, timer_dev, adc_dev, gpio_bit, timer_ch, adc_ch }
+
+namespace wirish {
+ namespace priv {
+
+ /*
+ * Chip-specific initialization data
+ */
+
+ extern rcc_pll_cfg w_board_pll_cfg;
+ extern adc_prescaler w_adc_pre;
+ extern adc_smp_rate w_adc_smp;
+
+ /*
+ * Chip-specific initialization routines and helper functions.
+ */
+
+ void board_reset_pll(void);
+ void board_setup_clock_prescalers(void);
+ void board_setup_gpio(void);
+ void board_setup_usb(void);
+ void series_init(void);
+
+ }
+}
+
+#endif
diff --git a/wirish/comm/HardwareSerial.cpp b/wirish/comm/HardwareSerial.cpp
deleted file mode 100644
index 6ef9222..0000000
--- a/wirish/comm/HardwareSerial.cpp
+++ /dev/null
@@ -1,119 +0,0 @@
-/******************************************************************************
- * The MIT License
- *
- * Copyright (c) 2010 Perry Hung.
- *
- * Permission is hereby granted, free of charge, to any person
- * obtaining a copy of this software and associated documentation
- * files (the "Software"), to deal in the Software without
- * restriction, including without limitation the rights to use, copy,
- * modify, merge, publish, distribute, sublicense, and/or sell copies
- * of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be
- * included in all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
- * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
- * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
- * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
- * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
- * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
- * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
- * SOFTWARE.
- *****************************************************************************/
-
-/**
- * @file HardwareSerial.cpp
- * @brief Wirish serial port implementation.
- */
-
-#include "libmaple.h"
-#include "gpio.h"
-#include "timer.h"
-
-#include "HardwareSerial.h"
-#include "boards.h"
-
-#define TX1 BOARD_USART1_TX_PIN
-#define RX1 BOARD_USART1_RX_PIN
-#define TX2 BOARD_USART2_TX_PIN
-#define RX2 BOARD_USART2_RX_PIN
-#define TX3 BOARD_USART3_TX_PIN
-#define RX3 BOARD_USART3_RX_PIN
-#if defined STM32_HIGH_DENSITY && !defined(BOARD_maple_RET6)
-#define TX4 BOARD_UART4_TX_PIN
-#define RX4 BOARD_UART4_RX_PIN
-#define TX5 BOARD_UART5_TX_PIN
-#define RX5 BOARD_UART5_RX_PIN
-#endif
-
-HardwareSerial Serial1(USART1, TX1, RX1, STM32_PCLK2);
-HardwareSerial Serial2(USART2, TX2, RX2, STM32_PCLK1);
-HardwareSerial Serial3(USART3, TX3, RX3, STM32_PCLK1);
-#if defined(STM32_HIGH_DENSITY) && !defined(BOARD_maple_RET6)
-HardwareSerial Serial4(UART4, TX4, RX4, STM32_PCLK1);
-HardwareSerial Serial5(UART5, TX5, RX5, STM32_PCLK1);
-#endif
-
-HardwareSerial::HardwareSerial(usart_dev *usart_device,
- uint8 tx_pin,
- uint8 rx_pin,
- uint32 clock_speed) {
- this->usart_device = usart_device;
- this->clock_speed = clock_speed;
- this->tx_pin = tx_pin;
- this->rx_pin = rx_pin;
-}
-
-/*
- * Set up/tear down
- */
-
-void HardwareSerial::begin(uint32 baud) {
- ASSERT(baud <= usart_device->max_baud);
-
- if (baud > usart_device->max_baud) {
- return;
- }
-
- const stm32_pin_info *txi = &PIN_MAP[tx_pin];
- const stm32_pin_info *rxi = &PIN_MAP[rx_pin];
-
- gpio_set_mode(txi->gpio_device, txi->gpio_bit, GPIO_AF_OUTPUT_PP);
- gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, GPIO_INPUT_FLOATING);
-
- if (txi->timer_device != NULL) {
- /* Turn off any PWM if there's a conflict on this GPIO bit. */
- timer_set_mode(txi->timer_device, txi->timer_channel, TIMER_DISABLED);
- }
-
- usart_init(usart_device);
- usart_set_baud_rate(usart_device, clock_speed, baud);
- usart_enable(usart_device);
-}
-
-void HardwareSerial::end(void) {
- usart_disable(usart_device);
-}
-
-/*
- * I/O
- */
-
-uint8 HardwareSerial::read(void) {
- return usart_getc(usart_device);
-}
-
-uint32 HardwareSerial::available(void) {
- return usart_data_available(usart_device);
-}
-
-void HardwareSerial::write(unsigned char ch) {
- usart_putc(usart_device, ch);
-}
-
-void HardwareSerial::flush(void) {
- usart_reset_rx(usart_device);
-}
diff --git a/wirish/ext_interrupts.cpp b/wirish/ext_interrupts.cpp
index b7f96f9..a3e61fd 100644
--- a/wirish/ext_interrupts.cpp
+++ b/wirish/ext_interrupts.cpp
@@ -2,6 +2,7 @@
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
@@ -25,17 +26,16 @@
*****************************************************************************/
/**
- * @file ext_interrupts.c
- *
- * @brief Wiring-like interface for external interrupts
+ * @file wirish/ext_interrupts.cpp
+ * @brief Wiring-like interface for external interrupts
*/
-#include "ext_interrupts.h"
+#include <wirish/ext_interrupts.h>
-#include "gpio.h"
-#include "exti.h"
+#include <libmaple/gpio.h>
+#include <libmaple/exti.h>
-#include "boards.h"
+#include <wirish/boards.h>
static inline exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode);
@@ -53,7 +53,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_bit),
+ exti_attach_interrupt((exti_num)(PIN_MAP[pin].gpio_bit),
gpio_exti_port(PIN_MAP[pin].gpio_device),
handler,
outMode);
@@ -68,7 +68,7 @@ void detachInterrupt(uint8 pin) {
return;
}
- exti_detach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_bit));
+ exti_detach_interrupt((exti_num)(PIN_MAP[pin].gpio_bit));
}
static inline exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode) {
diff --git a/wirish/comm/HardwareSPI.h b/wirish/include/wirish/HardwareSPI.h
index d138910..a1a4a73 100644
--- a/wirish/comm/HardwareSPI.h
+++ b/wirish/include/wirish/HardwareSPI.h
@@ -25,7 +25,7 @@
*****************************************************************************/
/**
- * @file HardwareSPI.h
+ * @file wirish/include/wirish/HardwareSPI.h
* @brief High-level SPI interface
*
* This is a "bare essentials" polling driver for now.
@@ -33,13 +33,13 @@
/* TODO [0.1.0] Remove deprecated methods. */
-#include "libmaple_types.h"
-#include "spi.h"
+#include <libmaple/libmaple_types.h>
+#include <libmaple/spi.h>
-#include "boards.h"
+#include <wirish/boards.h>
-#ifndef _HARDWARESPI_H_
-#define _HARDWARESPI_H_
+#ifndef _WIRISH_HARDWARESPI_H_
+#define _WIRISH_HARDWARESPI_H_
/**
* @brief Defines the possible SPI communication speeds.
@@ -184,6 +184,14 @@ public:
*/
uint8 nssPin(void);
+ /* Escape hatch */
+
+ /**
+ * @brief Get a pointer to the underlying libmaple spi_dev for
+ * this HardwareSPI instance.
+ */
+ spi_dev* c_dev(void) { return this->spi_d; }
+
/* -- The following methods are deprecated --------------------------- */
/**
@@ -220,4 +228,3 @@ private:
};
#endif
-
diff --git a/wirish/comm/HardwareSerial.h b/wirish/include/wirish/HardwareSerial.h
index f69b67a..f25362b 100644
--- a/wirish/comm/HardwareSerial.h
+++ b/wirish/include/wirish/HardwareSerial.h
@@ -2,6 +2,7 @@
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
@@ -25,17 +26,17 @@
*****************************************************************************/
/**
- * @file HardwareSerial.h
+ * @file wirish/include/wirish/HardwareSerial.h
* @brief Wirish serial port interface.
*/
-#ifndef _HARDWARESERIAL_H_
-#define _HARDWARESERIAL_H_
+#ifndef _WIRISH_HARDWARESERIAL_H_
+#define _WIRISH_HARDWARESERIAL_H_
-#include "libmaple_types.h"
-#include "usart.h"
+#include <libmaple/libmaple_types.h>
-#include "Print.h"
+#include <wirish/Print.h>
+#include <wirish/boards.h>
/*
* IMPORTANT:
@@ -47,12 +48,13 @@
* the documentation accordingly.
*/
+struct usart_dev;
+
class HardwareSerial : public Print {
public:
- HardwareSerial(usart_dev *usart_device,
+ HardwareSerial(struct usart_dev *usart_device,
uint8 tx_pin,
- uint8 rx_pin,
- uint32 clock_speed);
+ uint8 rx_pin);
/* Set up/tear down */
void begin(uint32 baud);
@@ -68,19 +70,33 @@ public:
/* Pin accessors */
int txPin(void) { return this->tx_pin; }
int rxPin(void) { return this->rx_pin; }
+
+ /* Escape hatch into libmaple */
+ /* FIXME [0.0.13] documentation */
+ struct usart_dev* c_dev(void) { return this->usart_device; }
private:
- usart_dev *usart_device;
+ struct usart_dev *usart_device;
uint8 tx_pin;
uint8 rx_pin;
- uint32 clock_speed;
};
+#if BOARD_HAVE_USART1
extern HardwareSerial Serial1;
+#endif
+#if BOARD_HAVE_USART2
extern HardwareSerial Serial2;
+#endif
+#if BOARD_HAVE_USART3
extern HardwareSerial Serial3;
-#if defined(STM32_HIGH_DENSITY) && !defined(BOARD_maple_RET6)
+#endif
+#if BOARD_HAVE_UART4
extern HardwareSerial Serial4;
+#endif
+#if BOARD_HAVE_UART5
extern HardwareSerial Serial5;
#endif
+#if BOARD_HAVE_USART6
+extern HardwareSerial Serial6;
+#endif
#endif
diff --git a/wirish/HardwareTimer.h b/wirish/include/wirish/HardwareTimer.h
index 1c34b9d..22aa010 100644
--- a/wirish/HardwareTimer.h
+++ b/wirish/include/wirish/HardwareTimer.h
@@ -28,19 +28,16 @@
* @brief Wirish timer class.
*/
-#ifndef _HARDWARETIMER_H_
-#define _HARDWARETIMER_H_
+#ifndef _WIRISH_HARDWARETIMER_H_
+#define _WIRISH_HARDWARETIMER_H_
// TODO [0.1.0] Remove deprecated pieces, pick a better API
-#include "timer.h"
+#include <libmaple/timer.h>
/** Timer mode. */
typedef timer_mode TimerMode;
-/** @brief Deprecated; use TIMER_OUTPUT_COMPARE instead. */
-#define TIMER_OUTPUTCOMPARE TIMER_OUTPUT_COMPARE
-
/**
* @brief Interface to one of the 16-bit timer peripherals.
*/
@@ -208,7 +205,15 @@ public:
*/
void refresh(void);
- /* -- Deprecated methods ----------------------------------------------- */
+ /* Escape hatch */
+
+ /**
+ * @brief Get a pointer to the underlying libmaple timer_dev for
+ * this HardwareTimer instance.
+ */
+ timer_dev* c_dev(void) { return this->dev; }
+
+/* -- The rest of this file is deprecated. --------------------------------- */
/** @brief Deprecated; use setMode(channel, mode) instead. */
void setChannelMode(int channel, timer_mode mode) {
@@ -287,7 +292,8 @@ public:
void generateUpdate(void) { refresh(); }
};
-/* -- The rest of this file is deprecated. --------------------------------- */
+/** @brief Deprecated; use TIMER_OUTPUT_COMPARE instead. */
+#define TIMER_OUTPUTCOMPARE TIMER_OUTPUT_COMPARE
/**
* @brief Deprecated.
@@ -313,7 +319,7 @@ extern HardwareTimer Timer3;
* Pre-instantiated timer.
*/
extern HardwareTimer Timer4;
-#ifdef STM32_HIGH_DENSITY
+#if (STM32_MCU_SERIES == STM32_SERIES_F1) && defined(STM32_HIGH_DENSITY)
/**
* @brief Deprecated.
*
diff --git a/wirish/Print.h b/wirish/include/wirish/Print.h
index c0c63cb..5fd0b7a 100644
--- a/wirish/Print.h
+++ b/wirish/include/wirish/Print.h
@@ -20,10 +20,10 @@
* Modified 12 April 2011 by Marti Bolivar <mbolivar@leaflabs.com>
*/
-#ifndef _PRINT_H_
-#define _PRINT_H_
+#ifndef _WIRISH_PRINT_H_
+#define _WIRISH_PRINT_H_
-#include "libmaple_types.h"
+#include <libmaple/libmaple_types.h>
enum {
BYTE = 0,
diff --git a/wirish/WProgram.h b/wirish/include/wirish/WProgram.h
index 2949a0a..b24ec2a 100644
--- a/wirish/WProgram.h
+++ b/wirish/include/wirish/WProgram.h
@@ -24,7 +24,12 @@
* SOFTWARE.
*****************************************************************************/
-#include "wirish.h"
+#ifndef _WIRISH_WPROGRAM_H_
+#define _WIRISH_WPROGRAM_H_
+
+#include <wirish/wirish.h>
void setup();
void loop();
+
+#endif
diff --git a/wirish/bit_constants.h b/wirish/include/wirish/bit_constants.h
index 8accc6b..4638f76 100644
--- a/wirish/bit_constants.h
+++ b/wirish/include/wirish/bit_constants.h
@@ -29,8 +29,8 @@
* compatibility.
*/
-#ifndef _BIT_CONSTANTS_H_
-#define _BIT_CONSTANTS_H_
+#ifndef _WIRISH_BIT_CONSTANTS_H_
+#define _WIRISH_BIT_CONSTANTS_H_
#define BIT0 (1 << 0)
#define BIT1 (1 << 1)
diff --git a/wirish/bits.h b/wirish/include/wirish/bits.h
index 3e755b7..0a63c58 100644
--- a/wirish/bits.h
+++ b/wirish/include/wirish/bits.h
@@ -27,4 +27,9 @@
/* Note: Use of this header file is deprecated. Use bit_constants.h
instead. */
-#include "bit_constants.h"
+#ifndef _WIRISH_BITS_H_
+#define _WIRISH_BITS_H_
+
+#include <wirish/bit_constants.h>
+
+#endif
diff --git a/wirish/boards.h b/wirish/include/wirish/boards.h
index 9ca4a66..6676a02 100644
--- a/wirish/boards.h
+++ b/wirish/include/wirish/boards.h
@@ -25,23 +25,18 @@
*****************************************************************************/
/**
- * @file boards.h
+ * @file wirish/include/wirish/boards.h
* @author Bryan Newbold <bnewbold@leaflabs.com>,
* Marti Bolivar <mbolivar@leaflabs.com>
- * @brief Board-specific pin information.
- *
- * To add a new board type, add a new pair of files to
- * /wirish/boards/, update the section below with a new "BOARD" type,
- * and update /wirish/rules.mk to include your boards/your_board.cpp
- * file in the top-level Makefile build.
+ * @brief init() and board-specific pin information.
*/
-#ifndef _BOARDS_H_
-#define _BOARDS_H_
-
-#include "libmaple_types.h"
+#ifndef _WIRISH_BOARDS_H_
+#define _WIRISH_BOARDS_H_
-#include "wirish_types.h"
+#include <libmaple/libmaple_types.h>
+#include <wirish/wirish_types.h>
+#include <board/board.h>
/* 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
@@ -115,41 +110,64 @@ extern void boardInit(void);
*/
bool boardUsesPin(uint8 pin);
-/* Include the appropriate private header from boards/: */
-
-/* FIXME HACK put boards/ before these paths once IDE uses make. */
-
-#ifdef BOARD_maple
-#include "maple.h"
-#elif defined(BOARD_maple_native)
-#include "maple_native.h"
-#elif defined(BOARD_maple_mini)
-#include "maple_mini.h"
-#elif defined(BOARD_maple_RET6)
/*
- * **NOT** MAPLE REV6. This the **Maple RET6 EDITION**, which is a
- * Maple with an STM32F103RET6 (...RET6) instead of an STM32F103RBT6
- * (...RBT6) on it. Maple Rev6 (as of March 2011) DOES NOT EXIST.
+ * Derived and default board definitions
*/
-#include "maple_RET6.h"
-#elif defined(BOARD_olimex_stm32_h103)
-#include "olimex_stm32_h103.h"
-#else
-/*
- * TODO turn this into a warning so people can:
- *
- * #include "my_board_config.h"
- * #include "wirish.h"
+
+#define CLOCK_SPEED_MHZ CYCLES_PER_MICROSECOND
+#define CLOCK_SPEED_HZ (CLOCK_SPEED_MHZ * 1000000UL)
+
+#ifndef SYSTICK_RELOAD_VAL
+#define SYSTICK_RELOAD_VAL (1000 * CYCLES_PER_MICROSECOND - 1)
+#endif
+
+#ifndef BOARD_BUTTON_PRESSED_LEVEL
+#define BOARD_BUTTON_PRESSED_LEVEL HIGH
+#endif
+
+/**
+ * @brief Does the board break out a USART/UART's RX and TX pins?
*
- * This will enable third-party board support without requiring that
- * anybody hack around in libmaple itself.
+ * BOARD_HAVE_USART(n) is nonzero iff USARTn is available (n must be
+ * an integer literal, 1 through 6). Also see BOARD_HAVE_USART1, ...,
+ * BOARD_HAVE_UART4 (sic), etc.
*/
-#error "Board type has not been selected correctly."
-#endif
+#define BOARD_HAVE_USART(n) (defined(BOARD_USART##n##_TX_PIN) && \
+ defined(BOARD_USART##n##_RX_PIN))
+/** Feature test: nonzero iff the board has USART1. */
+#define BOARD_HAVE_USART1 BOARD_HAVE_USART(1)
+/** Feature test: nonzero iff the board has USART2, 0 otherwise. */
+#define BOARD_HAVE_USART2 BOARD_HAVE_USART(2)
+/** Feature test: nonzero iff the board has USART3, 0 otherwise. */
+#define BOARD_HAVE_USART3 BOARD_HAVE_USART(3)
+/** Feature test: nonzero iff the board has UART4, 0 otherwise. */
+#define BOARD_HAVE_UART4 BOARD_HAVE_USART(4)
+/** Feature test: nonzero iff the board has UART5, 0 otherwise. */
+#define BOARD_HAVE_UART5 BOARD_HAVE_USART(5)
+/** Feature test: nonzero iff the board has USART6, 0 otherwise. */
+#define BOARD_HAVE_USART6 BOARD_HAVE_USART(6)
-/* Set derived definitions */
+/**
+ * @brief Does the board break out a SPI peripheral's pins?
+ *
+ * BOARD_HAVE_SPI(n) is nonzero iff SPIn is available (n must be an
+ * integer literal: 1, 2, or 3). Also see BOARD_HAVE_SPI1,
+ * BOARD_HAVE_SPI2, BOARD_HAVE_SPI3. */
+#define BOARD_HAVE_SPI(n) (defined(BOARD_SPI##n##_NSS_PIN) && \
+ defined(BOARD_SPI##n##_SCK_PIN) && \
+ defined(BOARD_SPI##n##_MISO_PIN) && \
+ defined(BOARD_SPI##n##_MOSI_PIN))
+/** Feature test: nonzero iff the board has SPI1. */
+#define BOARD_HAVE_SPI1 BOARD_HAVE_SPI(1)
+/** Feature test: nonzero iff the board has SPI2. */
+#define BOARD_HAVE_SPI2 BOARD_HAVE_SPI(2)
+/** Feature test: nonzero iff the board has SPI3. */
+#define BOARD_HAVE_SPI3 BOARD_HAVE_SPI(3)
-#define CLOCK_SPEED_MHZ CYCLES_PER_MICROSECOND
-#define CLOCK_SPEED_HZ (CLOCK_SPEED_MHZ * 1000000UL)
+/**
+ * @brief Feature test: nonzero iff the board has SerialUSB.
+ */
+#define BOARD_HAVE_SERIALUSB (defined(BOARD_USB_DISC_DEV) && \
+ defined(BOARD_USB_DISC_BIT))
#endif
diff --git a/wirish/ext_interrupts.h b/wirish/include/wirish/ext_interrupts.h
index b5c6f98..03b8e97 100644
--- a/wirish/ext_interrupts.h
+++ b/wirish/include/wirish/ext_interrupts.h
@@ -24,17 +24,16 @@
* SOFTWARE.
*****************************************************************************/
-#include "libmaple_types.h"
-#include "nvic.h"
-
/**
- * @file ext_interrupts.h
- *
- * @brief Wiring-like external interrupt prototypes and types.
+ * @file wirish/include/wirish/ext_interrupts.h
+ * @brief Wiring-like external interrupt prototypes and types.
*/
-#ifndef _EXT_INTERRUPTS_H_
-#define _EXT_INTERRUPTS_H_
+#ifndef _WIRISH_EXT_INTERRUPTS_H_
+#define _WIRISH_EXT_INTERRUPTS_H_
+
+#include <libmaple/libmaple_types.h>
+#include <libmaple/nvic.h>
/**
* The kind of transition on an external pin which should trigger an
diff --git a/wirish/io.h b/wirish/include/wirish/io.h
index 0cb9c04..08bbc06 100644
--- a/wirish/io.h
+++ b/wirish/include/wirish/io.h
@@ -25,17 +25,15 @@
*****************************************************************************/
/**
- * @file io.h
- *
- * @brief Arduino-compatible digital pin I/O interface.
+ * @file wirish/include/wirish/io.h
+ * @brief Wiring-style pin I/O interface.
*/
-#ifndef _IO_H_
-#define _IO_H_
-
-#include "libmaple_types.h"
+#ifndef _WIRISH_IO_H_
+#define _WIRISH_IO_H_
-#include "boards.h"
+#include <libmaple/libmaple_types.h>
+#include <wirish/boards.h>
/**
* Specifies a GPIO pin behavior.
@@ -183,7 +181,8 @@ static inline void toggleLED() {
*
* @see pinMode()
*/
-uint8 isButtonPressed();
+uint8 isButtonPressed(uint8 pin=BOARD_BUTTON_PIN,
+ uint32 pressedLevel=BOARD_BUTTON_PRESSED_LEVEL);
/**
* Wait until the button is pressed and released, timing out if no
diff --git a/wirish/pwm.h b/wirish/include/wirish/pwm.h
index a7705ab..6631d42 100644
--- a/wirish/pwm.h
+++ b/wirish/include/wirish/pwm.h
@@ -25,15 +25,14 @@
*****************************************************************************/
/**
- * @file pwm.h
- *
- * @brief Arduino-compatible PWM interface.
+ * @file wirish/include/wirish/pwm.h
+ * @brief Wiring-style PWM interface.
*/
-#ifndef _PWM_H_
-#define _PWM_H_
+#ifndef _WIRISH_PWM_H_
+#define _WIRISH_PWM_H_
-#include "libmaple_types.h"
+#include <libmaple/libmaple_types.h>
/**
* As a convenience, analogWrite is an alias of pwmWrite to ease
diff --git a/wirish/usb_serial.h b/wirish/include/wirish/usb_serial.h
index d43b288..f36671b 100644
--- a/wirish/usb_serial.h
+++ b/wirish/include/wirish/usb_serial.h
@@ -25,13 +25,14 @@
*****************************************************************************/
/**
- * @brief Wirish virtual serial port
+ * @brief Wirish USB virtual serial port (SerialUSB).
*/
-#ifndef _USB_SERIAL_H_
-#define _USB_SERIAL_H_
+#ifndef _WIRISH_USB_SERIAL_H_
+#define _WIRISH_USB_SERIAL_H_
-#include "Print.h"
+#include <wirish/Print.h>
+#include <wirish/boards.h>
/**
* @brief Virtual serial terminal.
@@ -58,7 +59,9 @@ public:
uint8 pending();
};
+#if BOARD_HAVE_SERIALUSB
extern USBSerial SerialUSB;
+#endif
#endif
diff --git a/wirish/wirish.h b/wirish/include/wirish/wirish.h
index d024f3b..4ebd66f 100644
--- a/wirish/wirish.h
+++ b/wirish/include/wirish/wirish.h
@@ -31,26 +31,30 @@
* substantial pieces of libmaple proper.
*/
-#ifndef _WIRISH_H_
-#define _WIRISH_H_
+#ifndef _WIRISH_WIRISH_H_
+#define _WIRISH_WIRISH_H_
-#include "boards.h"
-#include "io.h"
-#include "bit_constants.h"
-#include "pwm.h"
-#include "ext_interrupts.h"
-#include "wirish_debug.h"
-#include "wirish_math.h"
-#include "wirish_time.h"
-#include "HardwareSPI.h"
-#include "HardwareSerial.h"
-#include "HardwareTimer.h"
-#include "usb_serial.h"
+#include <libmaple/stm32.h>
-#include "libmaple.h"
-#include "wirish_types.h"
+#include <wirish/boards.h>
+#include <wirish/io.h>
+#include <wirish/bit_constants.h>
+#include <wirish/pwm.h>
+#include <wirish/ext_interrupts.h>
+#include <wirish/wirish_debug.h>
+#include <wirish/wirish_math.h>
+#include <wirish/wirish_time.h>
+#if STM32_MCU_SERIES == STM32_SERIES_F1 /* FIXME [0.0.13?] port to F2 */
+#include <wirish/HardwareSPI.h>
+#endif
+#include <wirish/HardwareSerial.h>
+#include <wirish/HardwareTimer.h>
+#include <wirish/usb_serial.h>
+#include <wirish/wirish_types.h>
+
+#include <libmaple/libmaple.h>
-/* Arduino wiring macros and bit defines */
+/* Wiring macros and bit defines */
#define true 0x1
#define false 0x0
diff --git a/wirish/wirish_debug.h b/wirish/include/wirish/wirish_debug.h
index 3f92b02..4edfd27 100644
--- a/wirish/wirish_debug.h
+++ b/wirish/include/wirish/wirish_debug.h
@@ -25,14 +25,14 @@
*****************************************************************************/
/**
- * @file wirish_debug.h
+ * @file wirish/include/wirish/wirish_debug.h
* @brief High level debug port configuration
*/
-#ifndef _WIRISH_DEBUG_H_
-#define _WIRISH_DEBUG_H_
+#ifndef _WIRISH_WIRISH_DEBUG_H_
+#define _WIRISH_WIRISH_DEBUG_H_
-#include "gpio.h"
+#include <libmaple/gpio.h>
/**
* @brief Disable the JTAG and Serial Wire (SW) debug ports.
@@ -42,9 +42,7 @@
*
* @see enableDebugPorts()
*/
-static inline void disableDebugPorts(void) {
- afio_cfg_debug_ports(AFIO_DEBUG_NONE);
-}
+void disableDebugPorts(void);
/**
* @brief Enable the JTAG and Serial Wire (SW) debug ports.
@@ -54,8 +52,6 @@ static inline void disableDebugPorts(void) {
*
* @see disableDebugPorts()
*/
-static inline void enableDebugPorts(void) {
- afio_cfg_debug_ports(AFIO_DEBUG_FULL_SWJ);
-}
+void enableDebugPorts(void);
#endif
diff --git a/wirish/wirish_math.h b/wirish/include/wirish/wirish_math.h
index a85b30a..39f16a0 100644
--- a/wirish/wirish_math.h
+++ b/wirish/include/wirish/wirish_math.h
@@ -25,12 +25,12 @@
*****************************************************************************/
/**
- * @file wirish_math.h
- * @brief Includes <math.h>; provides Arduino-compatible math routines.
+ * @file wirish/include/wirish/wirish_math.h
+ * @brief Includes <math.h>; provides Wiring-compatible math routines.
*/
-#ifndef _WIRING_MATH_H_
-#define _WIRING_MATH_H_
+#ifndef _WIRISH_WIRISH_MATH_H_
+#define _WIRISH_WIRISH_MATH_H_
#include <math.h>
diff --git a/wirish/wirish_time.h b/wirish/include/wirish/wirish_time.h
index 719a775..1520b1e 100644
--- a/wirish/wirish_time.h
+++ b/wirish/include/wirish/wirish_time.h
@@ -25,17 +25,17 @@
*****************************************************************************/
/**
- * @file wirish_time.h
+ * @file wirish/include/wirish/wirish_time.h
* @brief Timing and delay functions.
*/
-#ifndef _TIME_H_
-#define _TIME_H_
+#ifndef _WIRISH_WIRISH_TIME_H_
+#define _WIRISH_WIRISH_TIME_H_
-#include "libmaple_types.h"
-#include "systick.h"
+#include <libmaple/libmaple_types.h>
+#include <libmaple/systick.h>
-#include "boards.h"
+#include <wirish/boards.h>
#define US_PER_MS 1000
diff --git a/wirish/wirish_types.h b/wirish/include/wirish/wirish_types.h
index 43a6525..fce895e 100644
--- a/wirish/wirish_types.h
+++ b/wirish/include/wirish/wirish_types.h
@@ -25,18 +25,18 @@
*****************************************************************************/
/**
- * @file wirish_types.h
+ * @file wirish/include/wirish/wirish_types.h
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief Wirish library type definitions.
*/
-#include "libmaple_types.h"
-#include "gpio.h"
-#include "timer.h"
-#include "adc.h"
+#ifndef _WIRISH_WIRISH_TYPES_H_
+#define _WIRISH_WIRISH_TYPES_H_
-#ifndef _WIRISH_TYPES_H_
-#define _WIRISH_TYPES_H_
+#include <libmaple/libmaple_types.h>
+#include <libmaple/gpio.h>
+#include <libmaple/timer.h>
+#include <libmaple/adc.h>
/**
* Invalid stm32_pin_info adc_channel value.
diff --git a/wirish/pwm.cpp b/wirish/pwm.cpp
index 7e8a535..44884cd 100644
--- a/wirish/pwm.cpp
+++ b/wirish/pwm.cpp
@@ -2,6 +2,7 @@
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
@@ -25,21 +26,23 @@
*****************************************************************************/
/**
- * @brief Arduino-style PWM implementation.
+ * @file wirish/pwm.cpp
+ * @brief Wiring-style pwmWrite().
*/
-#include "pwm.h"
+#include <wirish/pwm.h>
-#include "libmaple_types.h"
-#include "timer.h"
+#include <libmaple/libmaple_types.h>
+#include <libmaple/timer.h>
-#include "boards.h"
+#include <wirish/boards.h>
void pwmWrite(uint8 pin, uint16 duty_cycle) {
- timer_dev *dev = PIN_MAP[pin].timer_device;
- if (pin >= BOARD_NR_GPIO_PINS || dev == NULL || dev->type == TIMER_BASIC) {
+ if (pin >= BOARD_NR_GPIO_PINS) {
return;
}
-
- timer_set_compare(dev, PIN_MAP[pin].timer_channel, duty_cycle);
+ timer_dev *dev = PIN_MAP[pin].timer_device;
+ uint8 cc_channel = PIN_MAP[pin].timer_channel;
+ ASSERT(dev && cc_channel);
+ timer_set_compare(dev, cc_channel, duty_cycle);
}
diff --git a/wirish/rules.mk b/wirish/rules.mk
index 1bf6245..1cac74a 100644
--- a/wirish/rules.mk
+++ b/wirish/rules.mk
@@ -3,37 +3,45 @@ sp := $(sp).x
dirstack_$(sp) := $(d)
d := $(dir)
BUILDDIRS += $(BUILD_PATH)/$(d)
-BUILDDIRS += $(BUILD_PATH)/$(d)/comm
-BUILDDIRS += $(BUILD_PATH)/$(d)/boards
-WIRISH_INCLUDES := -I$(d) -I$(d)/comm -I$(d)/boards
+# Add board directory and MCU-specific directory to BUILDDIRS. These
+# are in subdirectories, but they're logically part of the Wirish
+# submodule.
+WIRISH_BOARD_PATH := boards/$(BOARD)
+BUILDDIRS += $(BUILD_PATH)/$(d)/$(WIRISH_BOARD_PATH)
+BUILDDIRS += $(BUILD_PATH)/$(d)/$(MCU_SERIES)
-# Local flags
-CFLAGS_$(d) := $(WIRISH_INCLUDES) $(LIBMAPLE_INCLUDES)
+# Safe includes for Wirish.
+WIRISH_INCLUDES := -I$(d)/include -I$(d)/$(WIRISH_BOARD_PATH)/include
-# Local rules and targets
+# Local flags. Add -I$(d) to allow for private includes.
+CFLAGS_$(d) := $(LIBMAPLE_INCLUDES) $(WIRISH_INCLUDES) -I$(d)
+# Local rules and targets
sSRCS_$(d) := start.S
cSRCS_$(d) := start_c.c
-cppSRCS_$(d) := wirish_math.cpp \
- Print.cpp \
- boards.cpp \
- boards/maple.cpp \
- boards/maple_mini.cpp \
- boards/maple_native.cpp \
- boards/maple_RET6.cpp \
- boards/olimex_stm32_h103.cpp \
- comm/HardwareSerial.cpp \
- comm/HardwareSPI.cpp \
- HardwareTimer.cpp \
- usb_serial.cpp \
- cxxabi-compat.cpp \
- wirish_shift.cpp \
- wirish_analog.cpp \
- wirish_time.cpp \
- pwm.cpp \
- ext_interrupts.cpp \
- wirish_digital.cpp
+cSRCS_$(d) += syscalls.c
+cSRCS_$(d) += $(MCU_SERIES)/util_hooks.c
+cppSRCS_$(d) := boards.cpp
+cppSRCS_$(d) += cxxabi-compat.cpp
+cppSRCS_$(d) += ext_interrupts.cpp
+cppSRCS_$(d) += HardwareSerial.cpp
+cppSRCS_$(d) += HardwareTimer.cpp
+cppSRCS_$(d) += Print.cpp
+cppSRCS_$(d) += pwm.cpp
+ifeq ($(MCU_SERIES), stm32f1)
+cppSRCS_$(d) += usb_serial.cpp # HACK: this is currently STM32F1 only.
+cppSRCS_$(d) += HardwareSPI.cpp # FIXME: port to F2 and fix wirish.h
+endif
+cppSRCS_$(d) += wirish_analog.cpp
+cppSRCS_$(d) += wirish_digital.cpp
+cppSRCS_$(d) += wirish_math.cpp
+cppSRCS_$(d) += wirish_shift.cpp
+cppSRCS_$(d) += wirish_time.cpp
+cppSRCS_$(d) += $(MCU_SERIES)/boards_setup.cpp
+cppSRCS_$(d) += $(MCU_SERIES)/wirish_digital.cpp
+cppSRCS_$(d) += $(MCU_SERIES)/wirish_debug.cpp
+cppSRCS_$(d) += $(WIRISH_BOARD_PATH)/board.cpp
sFILES_$(d) := $(sSRCS_$(d):%=$(d)/%)
cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%)
diff --git a/wirish/stm32f1/boards_setup.cpp b/wirish/stm32f1/boards_setup.cpp
new file mode 100644
index 0000000..11872d5
--- /dev/null
+++ b/wirish/stm32f1/boards_setup.cpp
@@ -0,0 +1,89 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+*****************************************************************************/
+
+/**
+ * @file wirish/stm32f1/boards_setup.cpp
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief STM32F1 chip setup.
+ *
+ * This file controls how init() behaves on the STM32F1. Be very
+ * careful when changing anything here. Many of these values depend
+ * upon each other.
+ */
+
+#include "boards_private.h"
+
+#include <libmaple/gpio.h>
+#include <libmaple/timer.h>
+
+#include <wirish/boards.h>
+#include <wirish/usb_serial.h>
+
+// Allow boards to provide a PLL multiplier. This is useful for
+// e.g. STM32F100 value line MCUs, which use slower multipliers.
+// (We're leaving the default to RCC_PLLMUL_9 for now, since that
+// works for F103 performance line MCUs, which is all that LeafLabs
+// currently officially supports).
+#ifndef BOARD_RCC_PLLMUL
+#define BOARD_RCC_PLLMUL RCC_PLLMUL_9
+#endif
+
+namespace wirish {
+ namespace priv {
+
+ static stm32f1_rcc_pll_data pll_data = {BOARD_RCC_PLLMUL};
+ __weak rcc_pll_cfg w_board_pll_cfg = {RCC_PLLSRC_HSE, &pll_data};
+ __weak adc_prescaler w_adc_pre = ADC_PRE_PCLK2_DIV_6;
+ __weak adc_smp_rate w_adc_smp = ADC_SMPR_55_5;
+
+ __weak void board_reset_pll(void) {
+ // TODO
+ }
+
+ __weak void board_setup_clock_prescalers(void) {
+ rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1);
+ rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_2);
+ rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_1);
+ }
+
+ __weak void board_setup_gpio(void) {
+ gpio_init_all();
+ }
+
+ __weak void board_setup_usb(void) {
+#if BOARD_HAVE_SERIALUSB
+ SerialUSB.begin();
+#endif
+ }
+
+ __weak void series_init(void) {
+ // Initialize AFIO here, too, so peripheral remaps and external
+ // interrupts work out of the box.
+ afio_init();
+ }
+
+ }
+}
diff --git a/wirish/stm32f1/util_hooks.c b/wirish/stm32f1/util_hooks.c
new file mode 100644
index 0000000..8f798a1
--- /dev/null
+++ b/wirish/stm32f1/util_hooks.c
@@ -0,0 +1,83 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 Perry Hung (from libmaple/util.c).
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ *****************************************************************************/
+
+/*
+ * STM32F1 implementations for libmaple/util.c hooks
+ *
+ * These need more love and attention before being made public API
+ * (this includes being easily overridable by user code).
+ */
+
+#include <libmaple/nvic.h>
+#include <libmaple/gpio.h>
+#include <libmaple/stm32.h>
+#include <libmaple/timer.h>
+#include <libmaple/adc.h>
+#include <libmaple/usart.h>
+
+/* Failed ASSERT()s send out a message using this USART config. */
+#ifndef ERROR_USART
+#define ERROR_USART USART2
+#define ERROR_USART_BAUD 9600
+#define ERROR_TX_PORT GPIOA
+#define ERROR_TX_PIN 2
+#endif
+
+/*
+ * Disables all peripheral interrupts except USB (when available),
+ * turns off commonly-used peripherals. Called by __error() with
+ * global interrupts disabled.
+ */
+void __lm_error(void) {
+ /* Turn off peripheral interrupts */
+ nvic_irq_disable_all();
+
+ /* Turn off timers */
+ timer_disable_all();
+
+ /* Turn off ADC */
+ adc_disable_all();
+
+ /* Turn off all USARTs */
+ usart_disable_all();
+
+#if STM32_HAVE_USB
+ /* Turn the USB interrupt back on so the bootloader keeps on functioning */
+ nvic_irq_enable(NVIC_USB_HP_CAN_TX);
+ nvic_irq_enable(NVIC_USB_LP_CAN_RX0);
+#endif
+}
+
+/*
+ * Enable the error USART for writing.
+ */
+usart_dev* __lm_enable_error_usart() {
+ gpio_set_mode(ERROR_TX_PORT, ERROR_TX_PIN, GPIO_AF_OUTPUT_PP);
+ usart_init(ERROR_USART);
+ usart_set_baud_rate(ERROR_USART, USART_USE_PCLK, ERROR_USART_BAUD);
+ return ERROR_USART;
+}
diff --git a/wirish/stm32f1/wirish_debug.cpp b/wirish/stm32f1/wirish_debug.cpp
new file mode 100644
index 0000000..28de96d
--- /dev/null
+++ b/wirish/stm32f1/wirish_debug.cpp
@@ -0,0 +1,41 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ *****************************************************************************/
+
+/**
+ * @file wirish/stm32f1/wirish_debug.cpp
+ * @brief High level debug port configuration
+ */
+
+#include <wirish/wirish_debug.h>
+#include <libmaple/gpio.h>
+
+void disableDebugPorts(void) {
+ afio_cfg_debug_ports(AFIO_DEBUG_NONE);
+}
+
+void enableDebugPorts(void) {
+ afio_cfg_debug_ports(AFIO_DEBUG_FULL_SWJ);
+}
diff --git a/wirish/stm32f1/wirish_digital.cpp b/wirish/stm32f1/wirish_digital.cpp
new file mode 100644
index 0000000..8371b0e
--- /dev/null
+++ b/wirish/stm32f1/wirish_digital.cpp
@@ -0,0 +1,89 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ *****************************************************************************/
+
+/*
+ * STM32F1 implementations for basic GPIO functionality.
+ */
+
+#include <wirish/io.h>
+
+#include <libmaple/gpio.h>
+#include <libmaple/timer.h>
+
+#include <wirish/boards.h>
+
+void pinMode(uint8 pin, WiringPinMode mode) {
+ gpio_pin_mode outputMode;
+ bool pwm = false;
+
+ if (pin >= BOARD_NR_GPIO_PINS) {
+ return;
+ }
+
+ switch(mode) {
+ case OUTPUT:
+ outputMode = GPIO_OUTPUT_PP;
+ break;
+ case OUTPUT_OPEN_DRAIN:
+ outputMode = GPIO_OUTPUT_OD;
+ break;
+ case INPUT:
+ case INPUT_FLOATING:
+ outputMode = GPIO_INPUT_FLOATING;
+ break;
+ case INPUT_ANALOG:
+ outputMode = GPIO_INPUT_ANALOG;
+ break;
+ case INPUT_PULLUP:
+ outputMode = GPIO_INPUT_PU;
+ break;
+ case INPUT_PULLDOWN:
+ outputMode = GPIO_INPUT_PD;
+ break;
+ case PWM:
+ outputMode = GPIO_AF_OUTPUT_PP;
+ pwm = true;
+ break;
+ case PWM_OPEN_DRAIN:
+ outputMode = GPIO_AF_OUTPUT_OD;
+ pwm = true;
+ break;
+ default:
+ ASSERT(0);
+ return;
+ }
+
+ 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. */
+ timer_set_mode(PIN_MAP[pin].timer_device,
+ PIN_MAP[pin].timer_channel,
+ pwm ? TIMER_PWM : TIMER_DISABLED);
+ }
+}
diff --git a/wirish/stm32f2/boards_setup.cpp b/wirish/stm32f2/boards_setup.cpp
new file mode 100644
index 0000000..5764dd0
--- /dev/null
+++ b/wirish/stm32f2/boards_setup.cpp
@@ -0,0 +1,120 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ *****************************************************************************/
+
+/**
+ * @file wirish/stm32f2/boards_setup.cpp
+ * @author Marti Bolivar <mbolivar@leaflabs.com>
+ * @brief STM32F2 chip setup.
+ *
+ * This file controls how init() behaves on the STM32F2. Be very
+ * careful when changing anything here. Many of these values depend
+ * upon each other.
+ */
+
+#include "boards_private.h"
+
+#include <libmaple/gpio.h>
+#include <libmaple/syscfg.h>
+#include <libmaple/libmaple_types.h>
+#include <wirish/wirish_types.h>
+#include <board/board.h>
+
+// PLL config for 25 MHz external crystal --> 120 MHz SYSCLK, with
+// 48 MHz PLL48CK.
+#ifndef BOARD_PLL_Q
+#define BOARD_PLL_Q 5
+#endif
+#ifndef BOARD_PLL_P
+#define BOARD_PLL_P 2
+#endif
+#ifndef BOARD_PLL_N
+#define BOARD_PLL_N 240
+#endif
+#ifndef BOARD_PLL_M
+#define BOARD_PLL_M 25
+#endif
+
+static stm32f2_rcc_pll_data pll_data = {BOARD_PLL_Q,
+ BOARD_PLL_P,
+ BOARD_PLL_N,
+ BOARD_PLL_M};
+
+namespace wirish {
+ namespace priv {
+ // PLL clocked off of HSE, with above configuration data.
+ __weak rcc_pll_cfg w_board_pll_cfg = {RCC_PLLSRC_HSE, &pll_data};
+
+ // Global ADC prescaler
+ //
+ // On F2, with f_APB2 = 60 MHz, we need f_ADC = f_PCLK2 / 2 to
+ // get the (maximum) f_ADC = 30 MHz.
+ __weak adc_prescaler w_adc_pre = ADC_PRE_PCLK2_DIV_2;
+
+ // Conservative ADC sample rate. Goal is error less than 1/4
+ // LSB with 50 KOhm input impedance.
+ //
+ // On F2, with f_ADC = 30 MHz, error is acceptable assuming an
+ // internal sample and hold capacitance C_ADC at most 8.8 pF
+ // (ST doesn't specify the maximum C_ADC, so we had to take a
+ // guess). See Equation 1 and Table 61 in the F2 datasheet for
+ // more details.
+ __weak adc_smp_rate w_adc_smp = ADC_SMPR_144;
+
+ __weak void board_reset_pll(void) {
+ // Set PLLCFGR to its reset value.
+ RCC_BASE->PLLCFGR = 0x24003010; // FIXME lose the magic number.
+ }
+
+ __weak void board_setup_clock_prescalers(void) {
+ // On F2, with f_SYSCLK = 120 MHz (as determined by
+ // board_pll_cfg),
+ //
+ // f_AHB = f_SYSCLK / 1 = 120 MHz
+ // f_APB1 = f_AHB / 4 = 30 MHz
+ // f_APB2 = f_AHB / 2 = 60 MHz
+ rcc_set_prescaler(RCC_PRESCALER_AHB, RCC_AHB_SYSCLK_DIV_1);
+ rcc_set_prescaler(RCC_PRESCALER_APB1, RCC_APB1_HCLK_DIV_4);
+ rcc_set_prescaler(RCC_PRESCALER_APB2, RCC_APB2_HCLK_DIV_2);
+ }
+
+ __weak void board_setup_gpio(void) {
+ gpio_init_all();
+ }
+
+ __weak void board_setup_usb(void) {
+ // Nothing to do.
+ }
+
+ __weak void series_init(void) {
+ // We need SYSCFG for external interrupts
+ syscfg_init();
+ // Turn on the I/O compensation cell, since we drive the
+ // GPIOs quickly by default.
+ syscfg_enable_io_compensation();
+ }
+
+ }
+}
diff --git a/wirish/stm32f2/util_hooks.c b/wirish/stm32f2/util_hooks.c
new file mode 100644
index 0000000..1b519ab
--- /dev/null
+++ b/wirish/stm32f2/util_hooks.c
@@ -0,0 +1,45 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ *****************************************************************************/
+
+/*
+ * STM32F2 implementations for libmaple util.c hooks
+ * FIXME these are just minimal stubs
+ */
+
+#include <libmaple/nvic.h>
+
+/*
+ * Disables all peripheral interrupts. Called by __error() with global
+ * interrupts disabled.
+ */
+void __lm_error(void) {
+ nvic_irq_disable_all();
+}
+
+/*
+ * Enable the error USART for writing.
+ */
+/* usart_dev* __lm_enable_error_usart(void) { (TODO) } */
diff --git a/wirish/stm32f2/wirish_debug.cpp b/wirish/stm32f2/wirish_debug.cpp
new file mode 100644
index 0000000..af6c78b
--- /dev/null
+++ b/wirish/stm32f2/wirish_debug.cpp
@@ -0,0 +1,60 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ *****************************************************************************/
+
+/**
+ * @file wirish/stm32f2/wirish_debug.cpp
+ * @brief High level debug port configuration
+ */
+
+#include <wirish/wirish_debug.h>
+#include <libmaple/gpio.h>
+
+// TODO is it worth optimizing these into raw MODER and AFR[LH] writes?
+
+void disableDebugPorts(void) {
+ // PA13-PA15 and PB3-PB4 are in system alternate function mode on
+ // reset, to support JTAG. Just put them in input mode to release
+ // them.
+ gpio_set_mode(GPIOA, 13, GPIO_MODE_INPUT);
+ gpio_set_mode(GPIOA, 14, GPIO_MODE_INPUT);
+ gpio_set_mode(GPIOA, 15, GPIO_MODE_INPUT);
+ gpio_set_mode(GPIOB, 3, GPIO_MODE_INPUT);
+ gpio_set_mode(GPIOB, 4, GPIO_MODE_INPUT);
+}
+
+void enableDebugPorts(void) {
+ // Put PA13-PA15 and PB3-PB4 back in system AF mode.
+ gpio_set_mode(GPIOA, 13, GPIO_MODE_AF);
+ gpio_set_mode(GPIOA, 14, GPIO_MODE_AF);
+ gpio_set_mode(GPIOA, 15, GPIO_MODE_AF);
+ gpio_set_mode(GPIOB, 3, GPIO_MODE_AF);
+ gpio_set_mode(GPIOB, 4, GPIO_MODE_AF);
+ gpio_set_af(GPIOA, 13, GPIO_AF_SYS);
+ gpio_set_af(GPIOA, 14, GPIO_AF_SYS);
+ gpio_set_af(GPIOA, 15, GPIO_AF_SYS);
+ gpio_set_af(GPIOB, 3, GPIO_AF_SYS);
+ gpio_set_af(GPIOB, 4, GPIO_AF_SYS);
+}
diff --git a/wirish/stm32f2/wirish_digital.cpp b/wirish/stm32f2/wirish_digital.cpp
new file mode 100644
index 0000000..4d46f1c
--- /dev/null
+++ b/wirish/stm32f2/wirish_digital.cpp
@@ -0,0 +1,99 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ *****************************************************************************/
+
+/*
+ * STM32F2 implementations for basic GPIO functionality.
+ */
+
+#include <wirish/io.h>
+
+#include <libmaple/gpio.h>
+#include <libmaple/timer.h>
+
+#include <wirish/boards.h>
+
+void pinMode(uint8 pin, WiringPinMode w_mode) {
+ if (pin >= BOARD_NR_GPIO_PINS) {
+ return;
+ }
+
+ gpio_pin_mode mode;
+ // People always do the silly pin-toggle speed benchmark, so let's
+ // accomodate them:
+ unsigned flags = GPIO_MODEF_SPEED_HIGH;
+ bool pwm = false;
+ switch(w_mode) {
+ case OUTPUT:
+ mode = GPIO_MODE_OUTPUT;
+ break;
+ case OUTPUT_OPEN_DRAIN:
+ mode = GPIO_MODE_OUTPUT;
+ flags |= GPIO_MODEF_TYPE_OD;
+ break;
+ case INPUT:
+ case INPUT_FLOATING:
+ mode = GPIO_MODE_INPUT;
+ break;
+ case INPUT_ANALOG:
+ mode = GPIO_MODE_ANALOG;
+ break;
+ case INPUT_PULLUP:
+ mode = GPIO_MODE_INPUT;
+ flags |= GPIO_MODEF_PUPD_PU;
+ break;
+ case INPUT_PULLDOWN:
+ mode = GPIO_MODE_INPUT;
+ flags |= GPIO_MODEF_PUPD_PD;
+ break;
+ case PWM:
+ mode = GPIO_MODE_AF;
+ pwm = true;
+ break;
+ case PWM_OPEN_DRAIN:
+ mode = GPIO_MODE_AF;
+ flags |= GPIO_MODEF_TYPE_OD;
+ pwm = true;
+ break;
+ default:
+ ASSERT(0); // Can't happen
+ return;
+ }
+
+ const stm32_pin_info *info = &PIN_MAP[pin];
+
+ if (pwm) {
+ /* If enabling PWM, tell the timer to do PWM, and tell the pin
+ * to listen to the right timer. */
+ ASSERT(info->timer_device != NULL);
+ if (info->timer_device == NULL) {
+ return;
+ }
+ gpio_af timer_af = timer_get_af(info->timer_device);
+ timer_set_mode(info->timer_device, info->timer_channel, TIMER_PWM);
+ gpio_set_af(info->gpio_device, info->gpio_bit, timer_af);
+ }
+ gpio_set_modef(info->gpio_device, info->gpio_bit, mode, flags);
+}
diff --git a/wirish/syscalls.c b/wirish/syscalls.c
new file mode 100644
index 0000000..1e62d51
--- /dev/null
+++ b/wirish/syscalls.c
@@ -0,0 +1,170 @@
+/******************************************************************************
+ * The MIT License
+ *
+ * Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
+ *
+ * Permission is hereby granted, free of charge, to any person
+ * obtaining a copy of this software and associated documentation
+ * files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy,
+ * modify, merge, publish, distribute, sublicense, and/or sell copies
+ * of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+ * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
+ * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
+ * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ *****************************************************************************/
+
+/**
+ * @file wirish/syscalls.c
+ * @brief newlib stubs
+ *
+ * Low level system routines used by newlib for basic I/O and memory
+ * allocation. You can override most of these.
+ */
+
+#include <libmaple/libmaple.h>
+
+#include <sys/stat.h>
+#include <errno.h>
+
+/* If CONFIG_HEAP_START (or CONFIG_HEAP_END) isn't defined, then
+ * assume _lm_heap_start (resp. _lm_heap_end) is appropriately set by
+ * the linker */
+#ifndef CONFIG_HEAP_START
+extern char _lm_heap_start;
+#define CONFIG_HEAP_START ((caddr_t)&_lm_heap_start)
+#endif
+#ifndef CONFIG_HEAP_END
+extern char _lm_heap_end;
+#define CONFIG_HEAP_END ((caddr_t)&_lm_heap_end)
+#endif
+
+/*
+ * _sbrk -- Increment the program break.
+ *
+ * Get incr bytes more RAM (for use by the heap). malloc() and
+ * friends call this function behind the scenes.
+ */
+caddr_t _sbrk(int incr) {
+ static caddr_t pbreak = NULL; /* current program break */
+ caddr_t ret;
+
+ if (pbreak == NULL) {
+ pbreak = CONFIG_HEAP_START;
+ }
+
+ if ((CONFIG_HEAP_END - pbreak < incr) ||
+ (pbreak - CONFIG_HEAP_START < -incr)) {
+ errno = ENOMEM;
+ return (caddr_t)-1;
+ }
+
+ ret = pbreak;
+ pbreak += incr;
+ return ret;
+}
+
+__weak int _open(const char *path, int flags, ...) {
+ return 1;
+}
+
+__weak int _close(int fd) {
+ return 0;
+}
+
+__weak int _fstat(int fd, struct stat *st) {
+ st->st_mode = S_IFCHR;
+ return 0;
+}
+
+__weak int _isatty(int fd) {
+ return 1;
+}
+
+__weak int isatty(int fd) {
+ return 1;
+}
+
+__weak int _lseek(int fd, off_t pos, int whence) {
+ return -1;
+}
+
+__weak unsigned char getch(void) {
+ return 0;
+}
+
+
+__weak int _read(int fd, char *buf, size_t cnt) {
+ *buf = getch();
+
+ return 1;
+}
+
+__weak void putch(unsigned char c) {
+}
+
+__weak void cgets(char *s, int bufsize) {
+ char *p;
+ int c;
+ int i;
+
+ for (i = 0; i < bufsize; i++) {
+ *(s+i) = 0;
+ }
+// memset(s, 0, bufsize);
+
+ p = s;
+
+ for (p = s; p < s + bufsize-1;) {
+ c = getch();
+ switch (c) {
+ case '\r' :
+ case '\n' :
+ putch('\r');
+ putch('\n');
+ *p = '\n';
+ return;
+
+ case '\b' :
+ if (p > s) {
+ *p-- = 0;
+ putch('\b');
+ putch(' ');
+ putch('\b');
+ }
+ break;
+
+ default :
+ putch(c);
+ *p++ = c;
+ break;
+ }
+ }
+ return;
+}
+
+__weak int _write(int fd, const char *buf, size_t cnt) {
+ int i;
+
+ for (i = 0; i < cnt; i++)
+ putch(buf[i]);
+
+ return cnt;
+}
+
+/* Override fgets() in newlib with a version that does line editing */
+__weak char *fgets(char *s, int bufsize, void *f) {
+ cgets(s, bufsize);
+ return s;
+}
diff --git a/wirish/usb_serial.cpp b/wirish/usb_serial.cpp
index b66b992..a01900f 100644
--- a/wirish/usb_serial.cpp
+++ b/wirish/usb_serial.cpp
@@ -28,23 +28,33 @@
* @brief USB virtual serial terminal
*/
+#include <wirish/usb_serial.h>
+
#include <string.h>
-#include "wirish.h"
-#include "usb_cdcacm.h"
-#include "usb.h"
+#include <libmaple/usb_cdcacm.h>
+#include <libmaple/usb.h>
+
+#include <wirish/wirish.h>
#define USB_TIMEOUT 50
USBSerial::USBSerial(void) {
+#if !BOARD_HAVE_SERIALUSB
+ ASSERT(0);
+#endif
}
void USBSerial::begin(void) {
+#if BOARD_HAVE_SERIALUSB
usb_cdcacm_enable(BOARD_USB_DISC_DEV, BOARD_USB_DISC_BIT);
+#endif
}
void USBSerial::end(void) {
+#if BOARD_HAVE_SERIALUSB
usb_cdcacm_disable(BOARD_USB_DISC_DEV, BOARD_USB_DISC_BIT);
+#endif
}
void USBSerial::write(uint8 ch) {
@@ -114,4 +124,6 @@ uint8 USBSerial::getRTS(void) {
return usb_cdcacm_get_rts();
}
+#if BOARD_HAVE_SERIALUSB
USBSerial SerialUSB;
+#endif
diff --git a/wirish/wirish_analog.cpp b/wirish/wirish_analog.cpp
index e5b9ffc..91ca0e2 100644
--- a/wirish/wirish_analog.cpp
+++ b/wirish/wirish_analog.cpp
@@ -2,6 +2,7 @@
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2011, 2012 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
@@ -25,17 +26,17 @@
*****************************************************************************/
/**
- * @brief Arduino-compatible ADC implementation.
+ * @file wirish/wirish_analog.cpp
+ * @brief Wiring-style analogRead() implementation.
*/
-#include "io.h"
+#include <wirish/io.h>
+#include <libmaple/adc.h>
+#include <wirish/boards.h>
-#include "adc.h"
-
-#include "boards.h"
-
-/* Assumes that the ADC has been initialized and that the pin is set
- * to INPUT_ANALOG */
+/* Unlike Wiring and Arduino, this assumes that the pin's mode is set
+ * to INPUT_ANALOG. That's faster, but it does require some extra work
+ * on the user's part. Not too much, we think ;). */
uint16 analogRead(uint8 pin) {
const adc_dev *dev = PIN_MAP[pin].adc_device;
if (dev == NULL) {
diff --git a/wirish/wirish_digital.cpp b/wirish/wirish_digital.cpp
index 6a0577c..2711a33 100644
--- a/wirish/wirish_digital.cpp
+++ b/wirish/wirish_digital.cpp
@@ -2,6 +2,7 @@
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
+ * Copyright (c) 2012 LeafLabs, LLC.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
@@ -28,66 +29,13 @@
* Arduino-compatible digital I/O implementation.
*/
-#include "io.h"
+#include <wirish/io.h>
-#include "gpio.h"
-#include "timer.h"
-
-#include "wirish_time.h"
-#include "boards.h"
-
-void pinMode(uint8 pin, WiringPinMode mode) {
- gpio_pin_mode outputMode;
- bool pwm = false;
-
- if (pin >= BOARD_NR_GPIO_PINS) {
- return;
- }
-
- switch(mode) {
- case OUTPUT:
- outputMode = GPIO_OUTPUT_PP;
- break;
- case OUTPUT_OPEN_DRAIN:
- outputMode = GPIO_OUTPUT_OD;
- break;
- case INPUT:
- case INPUT_FLOATING:
- outputMode = GPIO_INPUT_FLOATING;
- break;
- case INPUT_ANALOG:
- outputMode = GPIO_INPUT_ANALOG;
- break;
- case INPUT_PULLUP:
- outputMode = GPIO_INPUT_PU;
- break;
- case INPUT_PULLDOWN:
- outputMode = GPIO_INPUT_PD;
- break;
- case PWM:
- outputMode = GPIO_AF_OUTPUT_PP;
- pwm = true;
- break;
- case PWM_OPEN_DRAIN:
- outputMode = GPIO_AF_OUTPUT_OD;
- pwm = true;
- break;
- default:
- ASSERT(0);
- return;
- }
-
- 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. */
- timer_set_mode(PIN_MAP[pin].timer_device,
- PIN_MAP[pin].timer_channel,
- pwm ? TIMER_PWM : TIMER_DISABLED);
- }
-}
+#include <libmaple/gpio.h>
+#include <libmaple/timer.h>
+#include <wirish/wirish_time.h>
+#include <wirish/boards.h>
uint32 digitalRead(uint8 pin) {
if (pin >= BOARD_NR_GPIO_PINS) {
@@ -116,10 +64,10 @@ void togglePin(uint8 pin) {
#define BUTTON_DEBOUNCE_DELAY 1
-uint8 isButtonPressed() {
- if (digitalRead(BOARD_BUTTON_PIN)) {
+uint8 isButtonPressed(uint8 pin, uint32 pressedLevel) {
+ if (digitalRead(pin) == pressedLevel) {
delay(BUTTON_DEBOUNCE_DELAY);
- while (digitalRead(BOARD_BUTTON_PIN))
+ while (digitalRead(pin) == pressedLevel)
;
return true;
}
diff --git a/wirish/wirish_math.cpp b/wirish/wirish_math.cpp
index 5aa6510..1443b3c 100644
--- a/wirish/wirish_math.cpp
+++ b/wirish/wirish_math.cpp
@@ -22,7 +22,7 @@
*/
#include <stdlib.h>
-#include "math.h"
+#include <wirish/wirish_math.h>
void randomSeed(unsigned int seed) {
if (seed != 0) {
diff --git a/wirish/wirish_shift.cpp b/wirish/wirish_shift.cpp
index f67364d..a032d50 100644
--- a/wirish/wirish_shift.cpp
+++ b/wirish/wirish_shift.cpp
@@ -1,40 +1,37 @@
-/*
- * wiring_shift.c - shiftOut() function
- * Part of Arduino - http://www.arduino.cc/
+/******************************************************************************
+ * The MIT License
*
- * Copyright (c) 2005-2006 David A. Mellis
+ * Copyright (c) 2012 LeafLabs, LLC.
*
- * This library is free software; you can redistribute it and/or
- * modify it under the terms of the GNU Lesser General Public License
- * as published by the Free Software Foundation; either version 2.1 of
- * the License, or (at your option) any later version.
+ * 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:
*
- * This library is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
- * Lesser General Public License for more details.
+ * The above copyright notice and this permission notice shall be
+ * included in all copies or substantial portions of the Software.
*
- * You should have received a copy of the GNU Lesser General Public
- * License along with this library; if not, write to the Free Software
- * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307
- * USA
- *
- * $Id: wiring.c 248 2007-02-03 15:36:30Z mellis $
- */
-
-#include "wirish.h"
-
-void shiftOut(uint8 dataPin, uint8 clockPin, uint8 bitOrder, uint8 val) {
- int i;
+ * 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.
+ *****************************************************************************/
- for (i = 0; i < 8; i++) {
- if (bitOrder == LSBFIRST) {
- digitalWrite(dataPin, !!(val & (1 << i)));
- } else {
- digitalWrite(dataPin, !!(val & (1 << (7 - i))));
- }
+#include <wirish/wirish.h>
- digitalWrite(clockPin, HIGH);
- digitalWrite(clockPin, LOW);
+void shiftOut(uint8 dataPin, uint8 clockPin, uint8 bitOrder, uint8 value) {
+ digitalWrite(clockPin, LOW);
+ for (int i = 0; i < 8; i++) {
+ int bit = bitOrder == LSBFIRST ? i : (7 - i);
+ digitalWrite(dataPin, (value >> bit) & 0x1);
+ togglePin(clockPin);
+ togglePin(clockPin);
}
}
diff --git a/wirish/wirish_time.cpp b/wirish/wirish_time.cpp
index c9f10a8..9ce934b 100644
--- a/wirish/wirish_time.cpp
+++ b/wirish/wirish_time.cpp
@@ -28,10 +28,10 @@
* @brief Delay implementation.
*/
-#include "wirish_time.h"
+#include <wirish/wirish_time.h>
-#include "libmaple_types.h"
-#include "delay.h"
+#include <libmaple/libmaple_types.h>
+#include <libmaple/delay.h>
void delay(unsigned long ms) {
uint32 i;