Merge remote-tracking branch 'rogerclarkmelbourne/master'

This commit is contained in:
Vassilis Serasidis 2015-08-23 11:45:36 +03:00
commit 863cf25f5b
52 changed files with 1811 additions and 46 deletions

View File

@ -203,7 +203,7 @@ genericSTM32F103C.menu.upload_method.BMPMethod.build.upload_flags=-DCONFIG_MAPLE
########################### Generic STM32F103R ###########################
genericSTM32F103R.name=Generic STM32F103R series
genericSTM32F103R.build.variant=generic_stm32f103r
#genericSTM32F103R.build.variant=generic_stm32f103r
genericSTM32F103R.build.vect=VECT_TAB_ADDR=0x8000000
genericSTM32F103R.build.core=maple
genericSTM32F103R.build.board=GENERIC_STM32F103R
@ -212,21 +212,32 @@ genericSTM32F103R.upload.file_type=bin
genericSTM32F103R.upload.auto_reset=true
#genericSTM32F103R.menu.device_variant.STM32F103RB=STM32F103RB
#genericSTM32F103R.menu.device_variant.STM32F103RB.build.cpu_flags=-DMCU_STM32F103RB
#genericSTM32F103R.menu.device_variant.STM32F103RB.upload.maximum_size=131072
#genericSTM32F103R.menu.device_variant.STM32F103RB.upload.ram.maximum_size=20480
#genericSTM32F103R.menu.device_variant.STM32F103RB.upload.flash.maximum_size=131072
#genericSTM32F103R.menu.device_variant.STM32F103RB.build.ldscript=ld/stm32f103rb.ld
genericSTM32F103R.menu.device_variant.STM32F103R8=STM32F103R8 (20k RAM. 64k Flash)
genericSTM32F103R.menu.device_variant.STM32F103R8.build.variant=generic_stm32f103r8
genericSTM32F103R.menu.device_variant.STM32F103R8.build.cpu_flags=-DMCU_STM32F103R8
genericSTM32F103R.menu.device_variant.STM32F103R8.upload.maximum_size=65536
genericSTM32F103R.menu.device_variant.STM32F103R8.upload.ram.maximum_size=20480
genericSTM32F103R.menu.device_variant.STM32F103R8.upload.flash.maximum_size=65536
genericSTM32F103R.menu.device_variant.STM32F103R8.build.ldscript=ld/stm32f103r8.ld
genericSTM32F103R.menu.device_variant.STM32F103RC=STM32F103RC
genericSTM32F103R.menu.device_variant.STM32F103RB=STM32F103RB (20k RAM. 128k Flash)
genericSTM32F103R.menu.device_variant.STM32F103RB.build.variant=generic_stm32f103r8
genericSTM32F103R.menu.device_variant.STM32F103RB.build.cpu_flags=-DMCU_STM32F103RB
genericSTM32F103R.menu.device_variant.STM32F103RB.upload.maximum_size=131072
genericSTM32F103R.menu.device_variant.STM32F103RB.upload.ram.maximum_size=20480
genericSTM32F103R.menu.device_variant.STM32F103RB.upload.flash.maximum_size=131072
genericSTM32F103R.menu.device_variant.STM32F103RB.build.ldscript=ld/stm32f103rb.ld
genericSTM32F103R.menu.device_variant.STM32F103RC=STM32F103RC (48k RAM. 256k Flash)
genericSTM32F103R.menu.device_variant.STM32F103RC.build.variant=generic_stm32f103r
genericSTM32F103R.menu.device_variant.STM32F103RC.build.cpu_flags=-DMCU_STM32F103RC
genericSTM32F103R.menu.device_variant.STM32F103RC.upload.maximum_size=262144
genericSTM32F103R.menu.device_variant.STM32F103RC.upload.ram.maximum_size=49152
genericSTM32F103R.menu.device_variant.STM32F103RC.upload.flash.maximum_size=262144
genericSTM32F103R.menu.device_variant.STM32F103RC.build.ldscript=ld/stm32f103rc.ld
genericSTM32F103R.menu.device_variant.STM32F103RE=STM32F103RE
genericSTM32F103R.menu.device_variant.STM32F103RE=STM32F103RE (64k RAM. 512k Flash)
genericSTM32F103R.menu.device_variant.STM32F103RE.build.variant=generic_stm32f103r
genericSTM32F103R.menu.device_variant.STM32F103RE.build.cpu_flags=-DMCU_STM32F103RE
genericSTM32F103R.menu.device_variant.STM32F103RE.upload.maximum_size=524288
genericSTM32F103R.menu.device_variant.STM32F103RE.upload.ram.maximum_size=65536
@ -241,7 +252,7 @@ genericSTM32F103R.menu.upload_method.DFUUploadMethod.upload.protocol=maple_dfu
genericSTM32F103R.menu.upload_method.DFUUploadMethod.upload.tool=maple_upload
genericSTM32F103R.menu.upload_method.DFUUploadMethod.build.upload_flags=-DSERIAL_USB -DGENERIC_BOOTLOADER
genericSTM32F103R.menu.upload_method.DFUUploadMethod.build.vect=VECT_TAB_ADDR=0x8002000
genericSTM32F103R.menu.upload_method.DFUUploadMethod.build.ldscript=ld/stm32f103re-bootloader.ld
genericSTM32F103R.menu.upload_method.DFUUploadMethod.build.ldscript=ld/bootloader.ld
genericSTM32F103R.menu.upload_method.DFUUploadMethod.upload.usbID=1EAF:0003
genericSTM32F103R.menu.upload_method.DFUUploadMethod.upload.altID=2

View File

@ -235,7 +235,7 @@ int32 i2c_master_xfer(i2c_dev *dev,
i2c_enable_irq(dev, I2C_IRQ_EVENT);
i2c_start_condition(dev);
rc = wait_for_state_change(dev, I2C_STATE_XFER_DONE, timeout);
if (rc < 0) {
goto out;
@ -347,9 +347,20 @@ void _i2c_irq_handler(i2c_dev *dev) {
* register. We should get another TXE interrupt
* immediately to fill DR again.
*/
if (msg->length != 1) {
if (msg->length > 1) {
i2c_write(dev, msg->data[msg->xferred++]);
}
} else if (msg->length == 0) { /* We're just sending an address */
i2c_stop_condition(dev);
/*
* Turn off event interrupts to keep BTF from firing until
* the end of the stop condition. Why on earth they didn't
* have a start/stop condition request clear BTF is beyond
* me.
*/
i2c_disable_irq(dev, I2C_IRQ_EVENT);
I2C_CRUMB(STOP_SENT, 0, 0);
dev->state = I2C_STATE_XFER_DONE;
} /* else we're just sending one byte */
}
sr1 = sr2 = 0;
}
@ -456,7 +467,7 @@ void _i2c_irq_handler(i2c_dev *dev) {
void _i2c_irq_error_handler(i2c_dev *dev) {
I2C_CRUMB(ERROR_ENTRY, dev->regs->SR1, dev->regs->SR2);
dev->error_flags = dev->regs->SR2 & (I2C_SR1_BERR |
dev->error_flags = dev->regs->SR1 & (I2C_SR1_BERR |
I2C_SR1_ARLO |
I2C_SR1_AF |
I2C_SR1_OVR);

View File

@ -365,7 +365,7 @@ uint8 SPIClass::transfer(uint8 byte) const {
*/
uint8 SPIClass::dmaTransfer(uint8 *transmitBuf, uint8 *receiveBuf, uint16 length) {
if (length == 0) return 0;
uint8 b;
uint8 b = 0;
if (spi_is_rx_nonempty(_currentSetting->spi_d) == 1) b = spi_rx_reg(_currentSetting->spi_d); //Clear the RX buffer in case a byte is waiting on it.
// dma1_ch3_Active=true;
dma_init(_currentSetting->spiDmaDev);
@ -427,7 +427,7 @@ uint8 SPIClass::dmaTransfer(uint8 *transmitBuf, uint8 *receiveBuf, uint16 length
uint8 SPIClass::dmaSend(uint8 *transmitBuf, uint16 length, bool minc) {
if (length == 0) return 0;
uint32 flags = ((DMA_MINC_MODE * minc) | DMA_FROM_MEM | DMA_TRNS_CMPLT);
uint8 b;
uint8 b = 0;
// dma1_ch3_Active=true;
dma_init(_currentSetting->spiDmaDev);
// dma_attach_interrupt(DMA1, DMA_CH3, &SPIClass::DMA1_CH3_Event);

View File

@ -40,11 +40,19 @@
uint8 HardWire::process() {
int8 res = i2c_master_xfer(sel_hard, &itc_msg, 1, 0);
if (res != 0) {
if (res == I2C_ERROR_PROTOCOL) {
if (sel_hard->error_flags & I2C_SR1_AF) { /* NACK */
res = (sel_hard->error_flags & I2C_SR1_ADDR ? ENACKADDR :
ENACKTRNS);
} else if (sel_hard->error_flags & I2C_SR1_OVR) { /* Over/Underrun */
res = EDATA;
} else { /* Bus or Arbitration error */
res = EOTHER;
}
i2c_disable(sel_hard);
i2c_master_enable(sel_hard, (I2C_BUS_RESET | dev_flags));
}
return 0;
return res;
}
// TODO: Add in Error Handling if devsel is out of range for other Maples
@ -56,7 +64,7 @@ HardWire::HardWire(uint8 dev_sel, uint8 flags) {
} else {
ASSERT(1);
}
dev_flags=flags;
dev_flags = flags;
}
HardWire::~HardWire() {

View File

@ -67,5 +67,5 @@ public:
void begin(uint8 = 0x00);
};
extern HardWire HWire;
#endif // _HARDWIRE_H_

View File

@ -191,4 +191,4 @@ TwoWire::~TwoWire() {
// Declare the instance that the users of the library can use
//TwoWire Wire(SCL, SDA, SOFT_STANDARD);
TwoWire Wire(PB6, PB7, SOFT_FAST);
TwoWire Wire(PB6, PB7, SOFT_STANDARD);

View File

@ -50,7 +50,7 @@
#define SDA 19
#define SCL 20
#define SOFT_STANDARD 16
#define SOFT_STANDARD 27
#define SOFT_FAST 0

View File

@ -61,11 +61,10 @@ void WireBase::beginTransmission(int slave_address) {
uint8 WireBase::endTransmission(void) {
uint8 retVal;
if (tx_buf_overflow) {
if (tx_buf_overflow) {
return EDATA;
}
retVal=process();// Changed so that the return value from process is returned by this function see also the return line below
retVal = process();// Changed so that the return value from process is returned by this function see also the return line below
tx_buf_idx = 0;
tx_buf_overflow = false;
return retVal;//SUCCESS;

View File

@ -0,0 +1,76 @@
// --------------------------------------
// i2c_scanner
//
// Version 1
// This program (or code that looks like it)
// can be found in many places.
// For example on the Arduino.cc forum.
// The original author is not know.
// Version 2, Juni 2012, Using Arduino 1.0.1
// Adapted to be as simple as possible by Arduino.cc user Krodal
// Version 3, Feb 26 2013
// V3 by louarnold
// Version 4, March 3, 2013, Using Arduino 1.0.3
// by Arduino.cc user Krodal.
// Changes by louarnold removed.
// Scanning addresses changed from 0...127 to 1...119,
// according to the i2c scanner by Nick Gammon
// http://www.gammon.com.au/forum/?id=10896
// Version 5, March 28, 2013
// As version 4, but address scans now to 127.
// A sensor seems to use address 120.
// Version 6, August 1, 2015
// Modified to support HardWire for STM32duino
//
// This sketch tests the standard 7-bit addresses
// Devices with higher bit address might not be seen properly.
//
#include <HardWire.h>
HardWire HWire(1, I2C_FAST_MODE); // I2c1
void setup() {
Serial.begin(115200);
HWire.begin();
Serial.println("\nI2C Scanner");
}
void loop() {
byte error, address;
int nDevices;
Serial.println("Scanning...");
nDevices = 0;
for(address = 1; address < 127; address++) {
// The i2c_scanner uses the return value of
// the Write.endTransmisstion to see if
// a device did acknowledge to the address.
HWire.beginTransmission(address);
error = HWire.endTransmission();
if (error == 0) {
Serial.print("I2C device found at address 0x");
if (address < 16)
Serial.print("0");
Serial.println(address, HEX);
nDevices++;
}
else if (error == 4) {
Serial.print("Unknown error at address 0x");
if (address < 16)
Serial.print("0");
Serial.println(address, HEX);
}
}
if (nDevices == 0)
Serial.println("No I2C devices found");
else
Serial.println("done");
delay(5000); // wait 5 seconds for next scan
}

View File

@ -0,0 +1,74 @@
// --------------------------------------
// i2c_scanner
//
// Version 1
// This program (or code that looks like it)
// can be found in many places.
// For example on the Arduino.cc forum.
// The original author is not know.
// Version 2, Juni 2012, Using Arduino 1.0.1
// Adapted to be as simple as possible by Arduino.cc user Krodal
// Version 3, Feb 26 2013
// V3 by louarnold
// Version 4, March 3, 2013, Using Arduino 1.0.3
// by Arduino.cc user Krodal.
// Changes by louarnold removed.
// Scanning addresses changed from 0...127 to 1...119,
// according to the i2c scanner by Nick Gammon
// http://www.gammon.com.au/forum/?id=10896
// Version 5, March 28, 2013
// As version 4, but address scans now to 127.
// A sensor seems to use address 120.
//
// This sketch tests the standard 7-bit addresses
// Devices with higher bit address might not be seen properly.
//
#include <Wire.h>
void setup() {
Serial.begin(115200);
Wire.begin();
Serial.println("\nI2C Scanner");
}
void loop() {
byte error, address;
int nDevices;
Serial.println("Scanning...");
nDevices = 0;
for(address = 1; address < 127; address++) {
// The i2c_scanner uses the return value of
// the Write.endTransmisstion to see if
// a device did acknowledge to the address.
Wire.beginTransmission(address);
error = Wire.endTransmission();
if (error == 0) {
Serial.print("I2C device found at address 0x");
if (address < 16)
Serial.print("0");
Serial.println(address, HEX);
nDevices++;
}
else if (error == 4) {
Serial.print("Unknown error at address 0x");
if (address < 16)
Serial.print("0");
Serial.println(address, HEX);
}
}
if (nDevices == 0)
Serial.println("No I2C devices found");
else
Serial.println("done");
delay(5000); // wait 5 seconds for next scan
}

View File

@ -255,7 +255,7 @@ extern timer_dev *TIMER14;
#define TIMER_SMCR_ETPS_DIV8 (0x3 << 12)
#define TIMER_SMCR_ETF (0xF << 12)
#define TIMER_SMCR_MSM (1U << TIMER_SMCR_MSM_BIT)
#define TIMER_SMCR_TS (0x3 << 4)
#define TIMER_SMCR_TS (0x7 << 4)
#define TIMER_SMCR_TS_ITR0 (0x0 << 4)
#define TIMER_SMCR_TS_ITR1 (0x1 << 4)
#define TIMER_SMCR_TS_ITR2 (0x2 << 4)
@ -264,7 +264,7 @@ extern timer_dev *TIMER14;
#define TIMER_SMCR_TS_TI1FP1 (0x5 << 4)
#define TIMER_SMCR_TS_TI2FP2 (0x6 << 4)
#define TIMER_SMCR_TS_ETRF (0x7 << 4)
#define TIMER_SMCR_SMS 0x3
#define TIMER_SMCR_SMS 0x7
#define TIMER_SMCR_SMS_DISABLED 0x0
#define TIMER_SMCR_SMS_ENCODER1 0x1
#define TIMER_SMCR_SMS_ENCODER2 0x2

View File

@ -0,0 +1,157 @@
/******************************************************************************
* 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_mini/board.cpp
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief Maple Mini board file.
*/
#include <board/board.h>
#include <libmaple/gpio.h>
#include <libmaple/timer.h>
/* Roger Clark. Added next to includes for changes to Serial */
#include <libmaple/usart.h>
#include <HardwareSerial.h>
#include <wirish_debug.h>
#include <wirish_types.h>
/* Since we want the Serial Wire/JTAG pins as GPIOs, disable both SW
* and JTAG debug support, unless configured otherwise. */
void boardInit(void) {
#ifndef CONFIG_MAPLE_MINI_NO_DISABLE_DEBUG
disableDebugPorts();
#endif
}
// Note. See the enum of pin names in board.h
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] = {
{GPIOA, TIMER2, ADC1, 0, 1, 0}, /* PA0 */
{GPIOA, TIMER2, ADC1, 1, 2, 1}, /* PA1 */
{GPIOA, TIMER2, ADC1, 2, 3, 2}, /* PA2 */
{GPIOA, TIMER2, ADC1, 3, 4, 3}, /* PA3 */
{GPIOA, NULL, ADC1, 4, 0, 4}, /* PA4 */
{GPIOA, NULL, ADC1, 5, 0, 5}, /* PA5 */
{GPIOA, TIMER3, ADC1, 6, 1, 6}, /* PA6 */
{GPIOA, TIMER3, ADC1, 7, 2, 7}, /* PA7 */
{GPIOA, TIMER1, NULL, 8, 1, ADCx}, /* PA8 */
{GPIOA, TIMER1, NULL, 9, 2, ADCx}, /* PA9 */
{GPIOA, TIMER1, NULL, 10, 3, ADCx}, /* PA10 */
{GPIOA, TIMER1, NULL, 11, 4, ADCx}, /* PA11 */
{GPIOA, NULL, NULL, 12, 0, ADCx}, /* PA12 */
{GPIOA, NULL, NULL, 13, 0, ADCx}, /* PA13 */
{GPIOA, NULL, NULL, 14, 0, ADCx}, /* PA14 */
{GPIOA, NULL, NULL, 15, 0, ADCx}, /* PA15 */
{GPIOB, TIMER3, ADC1, 0, 3, 8}, /* PB0 */
{GPIOB, TIMER3, ADC1, 1, 4, 9}, /* PB1 */
{GPIOB, NULL, NULL, 2, 0, ADCx}, /* PB2 */
{GPIOB, NULL, NULL, 3, 0, ADCx}, /* PB3 */
{GPIOB, NULL, NULL, 4, 0, ADCx}, /* PB4 */
{GPIOB, NULL, NULL, 5, 0, ADCx}, /* PB5 */
{GPIOB, TIMER4, NULL, 6, 1, ADCx}, /* PB6 */
{GPIOB, TIMER4, NULL, 7, 2, ADCx}, /* PB7 */
{GPIOB, TIMER4, NULL, 8, 3, ADCx}, /* PB8 */
{GPIOB, TIMER4, NULL, 9, 4, ADCx}, /* PB9 */
{GPIOB, NULL, NULL, 10, 0, ADCx}, /* PB10 */
{GPIOB, NULL, NULL, 11, 0, ADCx}, /* PB11 */
{GPIOB, NULL, NULL, 12, 0, ADCx}, /* PB12 */
{GPIOB, NULL, NULL, 13, 0, ADCx}, /* PB13 */
{GPIOB, NULL, NULL, 14, 0, ADCx}, /* PB14 */
{GPIOB, NULL, NULL, 15, 0, ADCx}, /* PB15 */
/* Andy Hull - the R8 is similar to the C8 but exposes more GPIO as follows */
{GPIOC, NULL, ADC1, 0, 0, 10}, /* PC0 */
{GPIOC, NULL, ADC1, 1, 0, 11}, /* PC1 */
{GPIOC, NULL, ADC1, 2, 0, 12}, /* PC2 */
{GPIOC, NULL, ADC1, 3, 0, 13}, /* PC3 */
{GPIOC, NULL, ADC1, 4, 0, 14}, /* PC4 */
{GPIOC, NULL, ADC1, 5, 0, 15}, /* PC5 */
{GPIOC, NULL, NULL, 6, 0, ADCx}, /* PC6 */
{GPIOC, NULL, NULL, 7, 0, ADCx}, /* PC7 */
{GPIOC, NULL, NULL, 8, 0, ADCx}, /* PC8 */
{GPIOC, NULL, NULL, 9, 0, ADCx}, /* PC9 */
{GPIOC, NULL, NULL, 10, 0, ADCx}, /* PC10 */
{GPIOC, NULL, NULL, 11, 0, ADCx}, /* PC11 */
{GPIOC, NULL, NULL, 12, 0, ADCx}, /* PC12 */
{GPIOC, NULL, NULL, 13, 0, ADCx}, /* PC13 */
{GPIOC, NULL, NULL, 14, 0, ADCx}, /* PC14 */
{GPIOC, NULL, NULL, 15, 0, ADCx}, /* PC15 */
{GPIOD, NULL, NULL, 2, 0, ADCx}, /* PD2 */
};
extern const uint8 boardPWMPins[BOARD_NR_PWM_PINS] __FLASH__ = {
PB0, PA7, PA6, PA3, PA2, PA1, PA0, PB7, PB6, PA10, PA9, PA8, PC6, PC7, PC8, PC9
};
extern const uint8 boardADCPins[BOARD_NR_ADC_PINS] __FLASH__ = {
PB0, PA7, PA6 , PA5 , PA4 , PA3 , PA2 , PA1 , PA0 , PC0, PC1, PC2, PC3, PC4, PC5
};
// Note. These defines are not really used by generic boards. They are for Maple Serial USB
#define USB_DP PA12
#define USB_DM PA11
// NOte. These definitions are not really used for generic boards, they only relate to boards modified to behave like Maple boards
extern const uint8 boardUsedPins[BOARD_NR_USED_PINS] __FLASH__ = {
USB_DP, USB_DM
};
/*
* Roger Clark
*
* 2015/05/28
*
* Moved definitions for Hardware Serial devices from HardwareSerial.cpp so that each board can define which Arduino "Serial" instance
* Maps to which hardware serial port on the microprocessor
*/
#ifdef SERIAL_USB
DEFINE_HWSERIAL(Serial1, 1);
DEFINE_HWSERIAL(Serial2, 2);
DEFINE_HWSERIAL(Serial3, 3);
#else
DEFINE_HWSERIAL(Serial, 1);
DEFINE_HWSERIAL(Serial1, 2);
DEFINE_HWSERIAL(Serial2, 3);
#endif

View File

@ -0,0 +1,84 @@
/******************************************************************************
* 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_mini/include/board/board.h
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief Maple Mini board header.
*
* See wirish/boards/maple/include/board/board.h for more information
* on these definitions.
*/
#ifndef _BOARD_GENERIC_STM32F103R8_H_
#define _BOARD_GENERIC_STM32F103R8_H_
#define CYCLES_PER_MICROSECOND 72
#define SYSTICK_RELOAD_VAL 71999 /* takes a cycle to reload */
#define BOARD_NR_USARTS 3
#define BOARD_USART1_TX_PIN PA9
#define BOARD_USART1_RX_PIN PA10
#define BOARD_USART2_TX_PIN PA2
#define BOARD_USART2_RX_PIN PA3
#define BOARD_USART3_TX_PIN PB10
#define BOARD_USART3_RX_PIN PB11
#define BOARD_NR_SPI 2
#define BOARD_SPI1_NSS_PIN PA4
#define BOARD_SPI1_MOSI_PIN PA7
#define BOARD_SPI1_MISO_PIN PA6
#define BOARD_SPI1_SCK_PIN PA5
#define BOARD_SPI2_NSS_PIN PB12
#define BOARD_SPI2_MOSI_PIN PB15
#define BOARD_SPI2_MISO_PIN PB14
#define BOARD_SPI2_SCK_PIN PB13
#define BOARD_NR_GPIO_PINS 49
#define BOARD_NR_PWM_PINS 16
#define BOARD_NR_ADC_PINS 15
#define BOARD_NR_USED_PINS 4
#define BOARD_JTMS_SWDIO_PIN 22
#define BOARD_JTCK_SWCLK_PIN 21
#define BOARD_JTDI_PIN 20
#define BOARD_JTDO_PIN 19
#define BOARD_NJTRST_PIN 18
#define BOARD_USB_DISC_DEV GPIOB
#define BOARD_USB_DISC_BIT 10
// Note this needs to match with the PIN_MAP array in board.cpp
enum {
PA0, PA1, PA2, PA3, PA4, PA5, PA6, PA7, PA8, PA9, PA10, PA11, PA12, PA13, PA14, PA15,
PB0, PB1, PB2, PB3, PB4, PB5, PB6, PB7, PB8, PB9, PB10, PB11, PB12, PB13, PB14, PB15,
PC0, PC1, PC2, PC3, PC4, PC5, PC6, PC7, PC8, PC9, PC10, PC11, PC12, PC13, PC14, PC15,
PD2
};
#endif

View File

@ -0,0 +1,18 @@
/*
* Linker script for Generic STM32F103RE boards, using the generic bootloader (which takes the lower 8k of memory)
*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
rom (rx) : ORIGIN = 0x08002000, LENGTH = 120K
}
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,30 @@
/*
* libmaple linker script for "Flash" builds.
*
* A Flash build puts .text (and .rodata) in Flash, and
* .data/.bss/heap (of course) in SRAM, but offsets the sections by
* enough space to store the Maple bootloader, which lives in low
* Flash and uses low memory.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
rom (rx) : ORIGIN = 0x08002000, LENGTH = 120K
}
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,220 @@
/*
* Linker script for libmaple.
*
* Original author "lanchon" from ST forums, with modifications by LeafLabs.
*/
OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
/*
* Configure other libraries we want in the link.
*
* libgcc, libc, and libm are common across supported toolchains.
* However, some toolchains require additional archives which aren't
* present everywhere (e.g. ARM's gcc-arm-embedded releases).
*
* To hack around this, we let the build system specify additional
* archives by putting the right extra_libs.inc (in a directory under
* toolchains/) in our search path.
*/
GROUP(libgcc.a libc.a libm.a)
INCLUDE extra_libs.inc
/*
* These force the linker to search for vector table symbols.
*
* These symbols vary by STM32 family (and also within families).
* It's up to the build system to configure the link's search path
* properly for the target MCU.
*/
INCLUDE vector_symbols.inc
/* STM32 vector table. */
EXTERN(__stm32_vector_table)
/* C runtime initialization function. */
EXTERN(start_c)
/* main entry point */
EXTERN(main)
/* Initial stack pointer value. */
EXTERN(__msp_init)
PROVIDE(__msp_init = ORIGIN(ram) + LENGTH(ram));
/* Reset vector and chip reset entry point */
EXTERN(__start__)
ENTRY(__start__)
PROVIDE(__exc_reset = __start__);
/* Heap boundaries, for libmaple */
EXTERN(_lm_heap_start);
EXTERN(_lm_heap_end);
SECTIONS
{
.text :
{
__text_start__ = .;
/*
* STM32 vector table. Leave this here. Yes, really.
*/
*(.stm32.interrupt_vector)
/*
* Program code and vague linking
*/
*(.text .text.* .gnu.linkonce.t.*)
*(.plt)
*(.gnu.warning)
*(.glue_7t) *(.glue_7) *(.vfp11_veneer)
*(.ARM.extab* .gnu.linkonce.armextab.*)
*(.gcc_except_table)
*(.eh_frame_hdr)
*(.eh_frame)
. = ALIGN(4);
KEEP(*(.init))
. = ALIGN(4);
__preinit_array_start = .;
KEEP (*(.preinit_array))
__preinit_array_end = .;
. = ALIGN(4);
__init_array_start = .;
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
__init_array_end = .;
. = ALIGN(0x4);
KEEP (*crtbegin.o(.ctors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*crtend.o(.ctors))
. = ALIGN(4);
KEEP(*(.fini))
. = ALIGN(4);
__fini_array_start = .;
KEEP (*(.fini_array))
KEEP (*(SORT(.fini_array.*)))
__fini_array_end = .;
KEEP (*crtbegin.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*crtend.o(.dtors))
} > REGION_TEXT
/*
* End of text
*/
.text.align :
{
. = ALIGN(8);
__text_end__ = .;
} > REGION_TEXT
/*
* .ARM.exidx exception unwinding; mandated by ARM's C++ ABI
*/
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > REGION_RODATA
__exidx_end = .;
/*
* .data
*/
.data :
{
__data_start__ = .;
LONG(0)
. = ALIGN(8);
*(.got.plt) *(.got)
*(.data .data.* .gnu.linkonce.d.*)
. = ALIGN(8);
__data_end__ = .;
} > REGION_DATA AT> REGION_RODATA
/*
* Read-only data
*/
.rodata :
{
*(.rodata .rodata.* .gnu.linkonce.r.*)
/* .USER_FLASH: We allow users to allocate into Flash here */
*(.USER_FLASH)
/* ROM image configuration; for C startup */
. = ALIGN(4);
_lm_rom_img_cfgp = .;
LONG(LOADADDR(.data));
/*
* Heap: Linker scripts may choose a custom heap by overriding
* _lm_heap_start and _lm_heap_end. Otherwise, the heap is in
* internal SRAM, beginning after .bss, and growing towards
* the stack.
*
* I'm shoving these here naively; there's probably a cleaner way
* to go about this. [mbolivar]
*/
_lm_heap_start = DEFINED(_lm_heap_start) ? _lm_heap_start : _end;
_lm_heap_end = DEFINED(_lm_heap_end) ? _lm_heap_end : __msp_init;
} > REGION_RODATA
/*
* .bss
*/
.bss :
{
. = ALIGN(8);
__bss_start__ = .;
*(.bss .bss.* .gnu.linkonce.b.*)
*(COMMON)
. = ALIGN (8);
__bss_end__ = .;
_end = __bss_end__;
} > REGION_BSS
/*
* Debugging sections
*/
.stab 0 (NOLOAD) : { *(.stab) }
.stabstr 0 (NOLOAD) : { *(.stabstr) }
/* DWARF debug sections.
* Symbols in the DWARF debugging sections are relative to the beginning
* of the section so we begin them at 0. */
/* DWARF 1 */
.debug 0 : { *(.debug) }
.line 0 : { *(.line) }
/* GNU DWARF 1 extensions */
.debug_srcinfo 0 : { *(.debug_srcinfo) }
.debug_sfnames 0 : { *(.debug_sfnames) }
/* DWARF 1.1 and DWARF 2 */
.debug_aranges 0 : { *(.debug_aranges) }
.debug_pubnames 0 : { *(.debug_pubnames) }
/* DWARF 2 */
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_line 0 : { *(.debug_line) }
.debug_frame 0 : { *(.debug_frame) }
.debug_str 0 : { *(.debug_str) }
.debug_loc 0 : { *(.debug_loc) }
.debug_macinfo 0 : { *(.debug_macinfo) }
/* SGI/MIPS DWARF 2 extensions */
.debug_weaknames 0 : { *(.debug_weaknames) }
.debug_funcnames 0 : { *(.debug_funcnames) }
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
.note.gnu.arm.ident 0 : { KEEP (*(.note.gnu.arm.ident)) }
.ARM.attributes 0 : { KEEP (*(.ARM.attributes)) }
/DISCARD/ : { *(.note.GNU-stack) }
}

View File

@ -0,0 +1,7 @@
/*
* Extra archives needed by ARM's GCC ARM Embedded arm-none-eabi-
* releases (https://launchpad.net/gcc-arm-embedded/).
*/
/* This is for the provided newlib. */
GROUP(libnosys.a)

View File

@ -0,0 +1,26 @@
/*
* libmaple linker script for "Flash" builds.
*
* A Flash build puts .text (and .rodata) in Flash, and
* .data/.bss/heap (of course) in SRAM, but offsets the sections by
* enough space to store the Maple bootloader, which lives in low
* Flash and uses low memory.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
INCLUDE mem-flash.inc
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,33 @@
/*
* libmaple linker script for "Flash" builds.
*
* A Flash build puts .text (and .rodata) in Flash, and
* .data/.bss/heap (of course) in SRAM, but offsets the sections by
* enough space to store the Maple bootloader, which lives in low
* Flash and uses low memory.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
/*INCLUDE mem-flash.inc*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 17K
rom (rx) : ORIGIN = 0x08000000, LENGTH = 44K
}
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,31 @@
/*
* libmaple linker script for "JTAG" builds.
*
* A "JTAG" build puts .text (and .rodata) in Flash, and
* .data/.bss/heap (of course) in SRAM, but links starting at the
* Flash and SRAM starting addresses (0x08000000 and 0x20000000
* respectively). This will wipe out a Maple bootloader if there's one
* on the board, so only use this if you know what you're doing.
*
* Of course, a "JTAG" build is perfectly usable for upload over SWD,
* the system memory bootloader, etc. The name is just a historical
* artifact.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
INCLUDE mem-jtag.inc
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,36 @@
/*
* libmaple linker script for "JTAG" builds.
*
* A "JTAG" build puts .text (and .rodata) in Flash, and
* .data/.bss/heap (of course) in SRAM, but links starting at the
* Flash and SRAM starting addresses (0x08000000 and 0x20000000
* respectively). This will wipe out a Maple bootloader if there's one
* on the board, so only use this if you know what you're doing.
*
* Of course, a "JTAG" build is perfectly usable for upload over SWD,
* the system memory bootloader, etc. The name is just a historical
* artifact.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K
}
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,5 @@
MEMORY
{
ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 17K
rom (rx) : ORIGIN = 0x08005000, LENGTH = 108K
}

View File

@ -0,0 +1,5 @@
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
}

View File

@ -0,0 +1,5 @@
MEMORY
{
ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 17K
rom (rx) : ORIGIN = 0x08005000, LENGTH = 0K
}

View File

@ -0,0 +1,25 @@
/*
* libmaple linker script for RAM builds.
*
* A Flash build puts .text, .rodata, and .data/.bss/heap (of course)
* in SRAM, but offsets the sections by enough space to store the
* Maple bootloader, which uses low memory.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
INCLUDE mem-ram.inc
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", ram);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", ram);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,31 @@
/*
* libmaple linker script for RAM builds.
*
* A Flash build puts .text, .rodata, and .data/.bss/heap (of course)
* in SRAM, but offsets the sections by enough space to store the
* Maple bootloader, which uses low memory.
*/
/*
* This pulls in the appropriate MEMORY declaration from the right
* subdirectory of stm32/mem/ (the environment must call ld with the
* right include directory flags to make this happen). Boards can also
* use this file to use any of libmaple's memory-related hooks (like
* where the heap should live).
*/
/*INCLUDE mem-ram.inc*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000C00, LENGTH = 17K
rom (rx) : ORIGIN = 0x08005000, LENGTH = 0
}
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", ram);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", ram);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,18 @@
/*
* Linker script for Generic STM32F103RB boards.
*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K
}
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,18 @@
/*
* Linker script for Generic STM32F103RB boards.
*/
MEMORY
{
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
}
/* Provide memory region aliases for common.inc */
REGION_ALIAS("REGION_TEXT", rom);
REGION_ALIAS("REGION_DATA", ram);
REGION_ALIAS("REGION_BSS", ram);
REGION_ALIAS("REGION_RODATA", rom);
/* Let common.inc handle the real work. */
INCLUDE common.inc

View File

@ -0,0 +1,78 @@
EXTERN(__msp_init)
EXTERN(__exc_reset)
EXTERN(__exc_nmi)
EXTERN(__exc_hardfault)
EXTERN(__exc_memmanage)
EXTERN(__exc_busfault)
EXTERN(__exc_usagefault)
EXTERN(__stm32reservedexception7)
EXTERN(__stm32reservedexception8)
EXTERN(__stm32reservedexception9)
EXTERN(__stm32reservedexception10)
EXTERN(__exc_svc)
EXTERN(__exc_debug_monitor)
EXTERN(__stm32reservedexception13)
EXTERN(__exc_pendsv)
EXTERN(__exc_systick)
EXTERN(__irq_wwdg)
EXTERN(__irq_pvd)
EXTERN(__irq_tamper)
EXTERN(__irq_rtc)
EXTERN(__irq_flash)
EXTERN(__irq_rcc)
EXTERN(__irq_exti0)
EXTERN(__irq_exti1)
EXTERN(__irq_exti2)
EXTERN(__irq_exti3)
EXTERN(__irq_exti4)
EXTERN(__irq_dma1_channel1)
EXTERN(__irq_dma1_channel2)
EXTERN(__irq_dma1_channel3)
EXTERN(__irq_dma1_channel4)
EXTERN(__irq_dma1_channel5)
EXTERN(__irq_dma1_channel6)
EXTERN(__irq_dma1_channel7)
EXTERN(__irq_adc)
EXTERN(__irq_usb_hp_can_tx)
EXTERN(__irq_usb_lp_can_rx0)
EXTERN(__irq_can_rx1)
EXTERN(__irq_can_sce)
EXTERN(__irq_exti9_5)
EXTERN(__irq_tim1_brk)
EXTERN(__irq_tim1_up)
EXTERN(__irq_tim1_trg_com)
EXTERN(__irq_tim1_cc)
EXTERN(__irq_tim2)
EXTERN(__irq_tim3)
EXTERN(__irq_tim4)
EXTERN(__irq_i2c1_ev)
EXTERN(__irq_i2c1_er)
EXTERN(__irq_i2c2_ev)
EXTERN(__irq_i2c2_er)
EXTERN(__irq_spi1)
EXTERN(__irq_spi2)
EXTERN(__irq_usart1)
EXTERN(__irq_usart2)
EXTERN(__irq_usart3)
EXTERN(__irq_exti15_10)
EXTERN(__irq_rtcalarm)
EXTERN(__irq_usbwakeup)
EXTERN(__irq_tim8_brk)
EXTERN(__irq_tim8_up)
EXTERN(__irq_tim8_trg_com)
EXTERN(__irq_tim8_cc)
EXTERN(__irq_adc3)
EXTERN(__irq_fsmc)
EXTERN(__irq_sdio)
EXTERN(__irq_tim5)
EXTERN(__irq_spi3)
EXTERN(__irq_uart4)
EXTERN(__irq_uart5)
EXTERN(__irq_tim6)
EXTERN(__irq_tim7)
EXTERN(__irq_dma2_channel1)
EXTERN(__irq_dma2_channel2)
EXTERN(__irq_dma2_channel3)
EXTERN(__irq_dma2_channel4_5)

View File

@ -0,0 +1,6 @@
// API compatibility
#include "variant.h"

View File

@ -0,0 +1,14 @@
#ifndef _VARIANT_ARDUINO_STM32_
#define _VARIANT_ARDUINO_STM32_
#define digitalPinToPort(P) ( PIN_MAP[P].gpio_device )
#define digitalPinToBitMask(P) ( BIT(PIN_MAP[P].gpio_bit) )
#define portOutputRegister(port) ( &(port->regs->ODR) )
#define portInputRegister(port) ( &(port->regs->IDR) )
#define portSetRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->BSRR) )
#define portClearRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->BRR) )
#define portConfigRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->CRL) )
#endif /* _VARIANT_ARDUINO_STM32_ */

View File

@ -0,0 +1,229 @@
/******************************************************************************
* 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/boards.cpp
* @brief init() and board routines.
*
* 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 <libmaple/libmaple_types.h>
#include <libmaple/flash.h>
#include <libmaple/nvic.h>
#include <libmaple/systick.h>
#include "boards_private.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);
/*
* Exported functions
*/
void init(void) {
setup_flash();
setup_clocks();
setup_nvic();
systick_init(SYSTICK_RELOAD_VAL);
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 boards with lots of pins. */
bool boardUsesPin(uint8 pin) {
for (int i = 0; i < BOARD_NR_USED_PINS; i++) {
if (pin == boardUsedPins[i]) {
return true;
}
}
return false;
}
/*
* Auxiliary routines
*/
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);
}
/*
* These addresses are where usercode starts when a bootloader is
* present. If no bootloader is present, the user NVIC usually starts
* at the Flash base address, 0x08000000.
*/
#if defined(BOOTLOADER_maple)
#define USER_ADDR_ROM 0x08005000
#else
#if defined(BOOTLOADER_robotis)
#define USER_ADDR_ROM 0x08003000
#else
#define USER_ADDR_ROM 0x08000000
#endif
#endif
#define USER_ADDR_RAM 0x20000C00
extern char __text_start__;
static void setup_nvic(void) {
nvic_init((uint32)VECT_TAB_ADDR, 0);
/* Roger Clark. We now control nvic vector table in boards.txt using the build.vect paramater
#ifdef VECT_TAB_FLASH
nvic_init(USER_ADDR_ROM, 0);
#elif defined VECT_TAB_RAM
nvic_init(USER_ADDR_RAM, 0);
#elif defined VECT_TAB_BASE
nvic_init((uint32)0x08000000, 0);
#elif defined VECT_TAB_ADDR
// A numerically supplied value
nvic_init((uint32)VECT_TAB_ADDR, 0);
#else
// Use the __text_start__ value from the linker script; this
// should be the start of the vector table.
nvic_init((uint32)&__text_start__, 0);
#endif
*/
}
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 setup_adcs(void) {
adc_set_prescaler(wirish::priv::w_adc_pre);
adc_foreach(adc_default_config);
}
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;
timer_init(dev);
timer_pause(dev);
regs->CR1 = TIMER_CR1_ARPE;
regs->PSC = 1;
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 (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);
}

View File

@ -0,0 +1,98 @@
/******************************************************************************
* 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 <boards.h>
#include <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) {
#ifdef SERIAL_USB
#ifdef GENERIC_BOOTLOADER
//Reset the USB interface on generic boards - developed by Victor PV
gpio_set_mode(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit, GPIO_OUTPUT_PP);
gpio_write_bit(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit,0);
for(volatile unsigned int i=0;i<256;i++);// Only small delay seems to be needed, and USB pins will get configured in Serial.begin
gpio_set_mode(PIN_MAP[PA12].gpio_device, PIN_MAP[PA12].gpio_bit, GPIO_INPUT_FLOATING);
#endif
Serial.begin();// Roger Clark. Changed SerialUSB to Serial for Arduino sketch compatibility
#endif
}
__weak void series_init(void) {
// Initialize AFIO here, too, so peripheral remaps and external
// interrupts work out of the box.
afio_init();
}
}
}

View File

@ -0,0 +1,57 @@
/******************************************************************************
* 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.
*****************************************************************************/
/*
* This file is a modified version of a file obtained from
* CodeSourcery Inc. (now part of Mentor Graphics Corp.), in which the
* following text appeared:
*
* The authors hereby grant permission to use, copy, modify, distribute,
* and license this software and its documentation for any purpose, provided
* that existing copyright notices are retained in all copies and that this
* notice is included verbatim in any distributions. No written agreement,
* license, or royalty fee is required for any of the authorized uses.
* Modifications to this software may be copyrighted by their authors
* and need not follow the licensing terms described here, provided that
* the new terms are clearly indicated on the first page of each file where
* they apply.
*/
.text
.code 16
.thumb_func
.globl __start__
.type __start__, %function
__start__:
.fnstart
ldr r1,=__msp_init
mov sp,r1
ldr r1,=start_c
bx r1
.pool
.cantunwind
.fnend

View File

@ -0,0 +1,95 @@
/******************************************************************************
* 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.
*****************************************************************************/
/*
* This file is a modified version of a file obtained from
* CodeSourcery Inc. (now part of Mentor Graphics Corp.), in which the
* following text appeared:
*
* Copyright (c) 2006, 2007 CodeSourcery Inc
*
* The authors hereby grant permission to use, copy, modify, distribute,
* and license this software and its documentation for any purpose, provided
* that existing copyright notices are retained in all copies and that this
* notice is included verbatim in any distributions. No written agreement,
* license, or royalty fee is required for any of the authorized uses.
* Modifications to this software may be copyrighted by their authors
* and need not follow the licensing terms described here, provided that
* the new terms are clearly indicated on the first page of each file where
* they apply.
*/
#include <stddef.h>
extern void __libc_init_array(void);
extern int main(int, char**, char**);
extern void exit(int) __attribute__((noreturn, weak));
/* The linker must ensure that these are at least 4-byte aligned. */
extern char __data_start__, __data_end__;
extern char __bss_start__, __bss_end__;
struct rom_img_cfg {
int *img_start;
};
extern char _lm_rom_img_cfgp;
void __attribute__((noreturn)) start_c(void) {
struct rom_img_cfg *img_cfg = (struct rom_img_cfg*)&_lm_rom_img_cfgp;
int *src = img_cfg->img_start;
int *dst = (int*)&__data_start__;
int exit_code;
/* Initialize .data, if necessary. */
if (src != dst) {
int *end = (int*)&__data_end__;
while (dst < end) {
*dst++ = *src++;
}
}
/* Zero .bss. */
dst = (int*)&__bss_start__;
while (dst < (int*)&__bss_end__) {
*dst++ = 0;
}
/* Run initializers. */
__libc_init_array();
/* Jump to main. */
exit_code = main(0, 0, 0);
if (exit) {
exit(exit_code);
}
/* If exit is NULL, make sure we don't return. */
for (;;)
continue;
}

View File

@ -0,0 +1,176 @@
/******************************************************************************
* 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>
#include <stddef.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 ((void *)&_lm_heap_start)
#endif
#ifndef CONFIG_HEAP_END
extern char _lm_heap_end;
#define CONFIG_HEAP_END ((void *)&_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.
*/
void *_sbrk(int incr) {
static void * pbreak = NULL; /* current program break */
void * ret;
if (pbreak == NULL) {
pbreak = CONFIG_HEAP_START;
}
if ((CONFIG_HEAP_END - pbreak < incr) ||
(pbreak - CONFIG_HEAP_START < -incr)) {
errno = ENOMEM;
return (void *)-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;
}
__weak void _exit(int exitcode) {
while (1)
;
}

View File

@ -138,10 +138,15 @@ int HardwareSerial::read(void) {
}
}
uint32 HardwareSerial::available(void) {
int HardwareSerial::available(void) {
return usart_data_available(usart_device);
}
int HardwareSerial::peek(void)
{
return usart_peek(usart_device);
}
uint32 HardwareSerial::pending(void) {
return usart_data_pending(usart_device);
}

View File

@ -35,7 +35,7 @@
#include "libmaple_types.h"
#include "usart.h"
#include "Print.h"
#include "Stream.h"
/*
* IMPORTANT:
@ -47,7 +47,7 @@
* the documentation accordingly.
*/
class HardwareSerial : public Print {
class HardwareSerial : public Stream {
public:
HardwareSerial(usart_dev *usart_device,
uint8 tx_pin,
@ -58,10 +58,11 @@ public:
void end(void);
/* I/O */
uint32 available(void);
virtual int available(void);
virtual int peek(void);
virtual void flush(void);
uint32 pending(void);
int read(void);
void flush(void);
virtual int read(void);
virtual size_t write(unsigned char);
using Print::write;

View File

@ -126,6 +126,25 @@ static inline uint8 rb_remove(ring_buffer *rb) {
return ch;
}
/*
* Roger Clark. 20141125,
* added peek function.
* @brief Return the first item from a ring buffer, without removing it
* @param rb Buffer to remove from, must contain at least one element.
*/
static inline int rb_peek(ring_buffer *rb)
{
if (rb->head == rb->tail)
{
return -1;
}
else
{
return rb->buf[rb->head];
}
}
/**
* @brief Attempt to remove the first item from a ring buffer.
*

View File

@ -323,6 +323,18 @@ static inline uint8 usart_getc(usart_dev *dev) {
return rb_remove(&dev->rbRX);
}
/*
* Roger Clark. 20141125,
* added peek function.
* @param dev Serial port to read from
* @return byte read
*/
static inline int usart_peek(usart_dev *dev)
{
return rb_peek(&dev->rbRX);
}
/**
* @brief Return the amount of data available in a serial port's RX buffer.
* @param dev Serial port to check

View File

@ -78,11 +78,11 @@ size_t USBSerial::write(const void *buf, uint32 len) {
return txed;
}
uint32 USBSerial::available(void) {
int USBSerial::available(void) {
return usbBytesAvailable();
}
uint32 USBSerial::read(void *buf, uint32 len) {
int USBSerial::read(void *buf, uint32 len) {
if (!buf) {
return 0;
}
@ -96,12 +96,38 @@ uint32 USBSerial::read(void *buf, uint32 len) {
}
/* Blocks forever until 1 byte is received */
uint8 USBSerial::read(void) {
int USBSerial::read(void) {
uint8 buf[1];
this->read(buf, 1);
return buf[0];
}
int USBSerial::peek(void)
{
// ThingToDo : Don't do any thing yet, since F4 doesn't have usb_cdcacm_peek() yet.
/*
uint8 b;
if (usb_cdcacm_peek(&b, 1)==1)
{
return b;
}
else */
{
return -1;
}
}
void USBSerial::flush(void)
{
/*Roger Clark. Rather slow method. Need to improve this */
uint8 b;
while(usbBytesAvailable())
{
this->read(&b, 1);
}
return;
}
uint8 USBSerial::pending(void) {
return usbGetPending();
}

View File

@ -31,12 +31,12 @@
#ifndef _USB_SERIAL_H_
#define _USB_SERIAL_H_
#include "Print.h"
#include "Stream.h"
/**
* @brief Virtual serial terminal.
*/
class USBSerial : public Print {
class USBSerial : public Stream {
public:
USBSerial(void);
@ -44,10 +44,12 @@ public:
void begin(int);
void end(void);
uint32 available(void);
virtual int available(void);
virtual int peek(void);
virtual void flush(void);
uint32 read(void *buf, uint32 len);
uint8 read(void);
virtual int read(void *buf, uint32 len);
virtual int read(void);
size_t write(uint8);
size_t write(const char *str);

View File

@ -33,6 +33,7 @@
#ifndef _WIRISH_H_
#define _WIRISH_H_
#include <stdlib.h>
#include "libmaple.h"
#include "wirish_types.h"

View File

@ -49,6 +49,9 @@ DhcpClass* UIPEthernetClass::_dhcp(NULL);
unsigned long UIPEthernetClass::periodic_timer;
static DhcpClass s_dhcp; // Placing this instance here is saving 40K to final *.bin (see bug below)
// Because uIP isn't encapsulated within a class we have to use global
// variables, so we can only have one TCP/IP stack per program.
@ -60,7 +63,8 @@ UIPEthernetClass::UIPEthernetClass()
int
UIPEthernetClass::begin(const uint8_t* mac)
{
static DhcpClass s_dhcp;
//static DhcpClass s_dhcp; // <-- this is a bug !
// I leave it there commented for history. It is bring all GCC "new" memory allocation code, making the *.bin almost 40K bigger. I've move it globally.
_dhcp = &s_dhcp;
// Initialise the basic info
init(mac);

View File

@ -0,0 +1,14 @@
#ifndef _VARIANT_ARDUINO_STM32_
#define _VARIANT_ARDUINO_STM32_
#define digitalPinToPort(P) ( PIN_MAP[P].gpio_device )
#define digitalPinToBitMask(P) ( BIT(PIN_MAP[P].gpio_bit) )
#define portOutputRegister(port) ( &(port->regs->ODR) )
#define portInputRegister(port) ( &(port->regs->IDR) )
#define portSetRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->BSRR) )
#define portClearRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->BRR) )
#define portConfigRegister(pin) ( &(PIN_MAP[pin].gpio_device->regs->CRL) )
#endif /* _VARIANT_ARDUINO_STM32_ */

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@ -37,4 +37,4 @@ if [ ! -x ${DFU_UTIL} ]; then
exit 2
fi
${DFU_UTIL} -d ${usbID} -a ${altID} -D ${binfile} ${dfuse_addr}
${DFU_UTIL} -d ${usbID} -a ${altID} -D ${binfile} ${dfuse_addr} -R

View File

@ -50,4 +50,4 @@ if [ ! -x ${DFU_UTIL} ]; then
exit 2
fi
${DFU_UTIL} -d ${usbID} -a ${altID} -D ${binfile} -R ${dfuse_addr}
${DFU_UTIL} -d ${usbID} -a ${altID} -D ${binfile} -R ${dfuse_addr} -R

View File

@ -1,2 +1,2 @@
#! /bin/sh
autoreconf -v -i
#! /bin/sh
autoreconf -v -i