first commit
This commit is contained in:
181
STM32ArduinoCompat/HardwareSPI.cpp
Normal file
181
STM32ArduinoCompat/HardwareSPI.cpp
Normal file
@@ -0,0 +1,181 @@
|
||||
// ArduinoCompat/HardwareSPI.cpp
|
||||
//
|
||||
// Interface between Arduino-like SPI interface and STM32F4 Discovery and similar
|
||||
// using STM32F4xx_DSP_StdPeriph_Lib_V1.3.0
|
||||
|
||||
#include <RadioHead.h>
|
||||
#if (RH_PLATFORM == RH_PLATFORM_STM32STD)
|
||||
|
||||
#include <wirish.h>
|
||||
#include <HardwareSPI.h>
|
||||
#include "stm32f4xx.h"
|
||||
#include "stm32f4xx_spi.h"
|
||||
extern "C"
|
||||
{
|
||||
#include "gdb_stdio.h"
|
||||
}
|
||||
|
||||
// Symbolic definitions for the SPI pins we intend to use
|
||||
// Currently we only support SPI1
|
||||
#define SPIx SPI1
|
||||
#define SPIx_CLK RCC_APB2Periph_SPI1
|
||||
#define SPIx_CLK_INIT RCC_APB2PeriphClockCmd
|
||||
#define SPIx_IRQn SPI2_IRQn
|
||||
#define SPIx_IRQHANDLER SPI2_IRQHandler
|
||||
|
||||
#define SPIx_SCK_PIN GPIO_Pin_5
|
||||
#define SPIx_SCK_GPIO_PORT GPIOA
|
||||
#define SPIx_SCK_GPIO_CLK RCC_AHB1Periph_GPIOA
|
||||
#define SPIx_SCK_SOURCE GPIO_PinSource5
|
||||
#define SPIx_SCK_AF GPIO_AF_SPI1
|
||||
|
||||
#define SPIx_MISO_PIN GPIO_Pin_6
|
||||
#define SPIx_MISO_GPIO_PORT GPIOA
|
||||
#define SPIx_MISO_GPIO_CLK RCC_AHB1Periph_GPIOA
|
||||
#define SPIx_MISO_SOURCE GPIO_PinSource6
|
||||
#define SPIx_MISO_AF GPIO_AF_SPI1
|
||||
|
||||
#define SPIx_MOSI_PIN GPIO_Pin_7
|
||||
#define SPIx_MOSI_GPIO_PORT GPIOA
|
||||
#define SPIx_MOSI_GPIO_CLK RCC_AHB1Periph_GPIOA
|
||||
#define SPIx_MOSI_SOURCE GPIO_PinSource7
|
||||
#define SPIx_MOSI_AF GPIO_AF_SPI1
|
||||
|
||||
HardwareSPI::HardwareSPI(uint32_t spiPortNumber) :
|
||||
_spiPortNumber(spiPortNumber)
|
||||
{
|
||||
}
|
||||
|
||||
void HardwareSPI::begin(SPIFrequency frequency, uint32_t bitOrder, uint32_t mode)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
// NVIC_InitTypeDef NVIC_InitStructure;
|
||||
SPI_InitTypeDef SPI_InitStructure;
|
||||
|
||||
/* Peripheral Clock Enable -------------------------------------------------*/
|
||||
/* Enable the SPI clock */
|
||||
RCC_APB2PeriphClockCmd(SPIx_CLK, ENABLE);
|
||||
|
||||
/* Enable GPIO clocks */
|
||||
RCC_AHB1PeriphClockCmd(SPIx_SCK_GPIO_CLK | SPIx_MISO_GPIO_CLK | SPIx_MOSI_GPIO_CLK, ENABLE);
|
||||
|
||||
/* SPI GPIO Configuration --------------------------------------------------*/
|
||||
/* GPIO Deinitialisation */
|
||||
GPIO_DeInit(SPIx_SCK_GPIO_PORT);
|
||||
GPIO_DeInit(SPIx_MISO_GPIO_PORT);
|
||||
GPIO_DeInit(SPIx_MOSI_GPIO_PORT);
|
||||
|
||||
/* Connect SPI pins to AF5 */
|
||||
GPIO_PinAFConfig(SPIx_SCK_GPIO_PORT, SPIx_SCK_SOURCE, SPIx_SCK_AF);
|
||||
GPIO_PinAFConfig(SPIx_MISO_GPIO_PORT, SPIx_MISO_SOURCE, SPIx_MISO_AF);
|
||||
GPIO_PinAFConfig(SPIx_MOSI_GPIO_PORT, SPIx_MOSI_SOURCE, SPIx_MOSI_AF);
|
||||
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
|
||||
|
||||
/* SPI SCK pin configuration */
|
||||
GPIO_InitStructure.GPIO_Pin = SPIx_SCK_PIN;
|
||||
GPIO_Init(SPIx_SCK_GPIO_PORT, &GPIO_InitStructure);
|
||||
|
||||
/* SPI MISO pin configuration */
|
||||
GPIO_InitStructure.GPIO_Pin = SPIx_MISO_PIN;
|
||||
GPIO_Init(SPIx_MISO_GPIO_PORT, &GPIO_InitStructure);
|
||||
|
||||
/* SPI MOSI pin configuration */
|
||||
GPIO_InitStructure.GPIO_Pin = SPIx_MOSI_PIN;
|
||||
GPIO_Init(SPIx_MOSI_GPIO_PORT, &GPIO_InitStructure);
|
||||
|
||||
/* SPI configuration -------------------------------------------------------*/
|
||||
SPI_I2S_DeInit(SPIx);
|
||||
SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
|
||||
SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
|
||||
if (mode == SPI_MODE0)
|
||||
{
|
||||
SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
|
||||
SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge;
|
||||
}
|
||||
else if (mode == SPI_MODE1)
|
||||
{
|
||||
SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
|
||||
SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge;
|
||||
}
|
||||
else if (mode == SPI_MODE2)
|
||||
{
|
||||
SPI_InitStructure.SPI_CPOL = SPI_CPOL_High;
|
||||
SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge;
|
||||
}
|
||||
else if (mode == SPI_MODE3)
|
||||
{
|
||||
SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
|
||||
SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge;
|
||||
}
|
||||
|
||||
SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
|
||||
// Prescaler is divided into PCLK2 (84MHz) to get SPI baud rate/clock speed
|
||||
// 256 => 328.125kHz
|
||||
// 128 => 656.25kHz
|
||||
// 64 => 1.3125MHz
|
||||
// 32 => 2.625MHz
|
||||
// 16 => 5.25MHz
|
||||
// 8 => 10.5MHz
|
||||
// 4 => 21.0MHz
|
||||
switch (frequency)
|
||||
{
|
||||
case SPI_21_0MHZ:
|
||||
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4;
|
||||
break;
|
||||
case SPI_10_5MHZ:
|
||||
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
|
||||
break;
|
||||
case SPI_5_25MHZ:
|
||||
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16;
|
||||
break;
|
||||
case SPI_2_625MHZ:
|
||||
default:
|
||||
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_32;
|
||||
break;
|
||||
case SPI_1_3125MHZ:
|
||||
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_64;
|
||||
break;
|
||||
case SPI_656_25KHZ:
|
||||
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_128;
|
||||
break;
|
||||
case SPI_328_125KHZ:
|
||||
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256;
|
||||
break;
|
||||
|
||||
}
|
||||
|
||||
if (bitOrder == LSBFIRST)
|
||||
SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_LSB;
|
||||
else
|
||||
SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
|
||||
SPI_InitStructure.SPI_CRCPolynomial = 7;
|
||||
SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
|
||||
|
||||
/* Initializes the SPI communication */
|
||||
SPI_Init(SPIx, &SPI_InitStructure);
|
||||
/* Enable SPI1 */
|
||||
SPI_Cmd(SPIx, ENABLE);
|
||||
}
|
||||
|
||||
void HardwareSPI::end(void)
|
||||
{
|
||||
SPI_DeInit(SPIx);
|
||||
}
|
||||
|
||||
uint8_t HardwareSPI::transfer(uint8_t data)
|
||||
{
|
||||
// Wait for TX empty
|
||||
while (SPI_I2S_GetFlagStatus(SPIx, SPI_I2S_FLAG_TXE) == RESET)
|
||||
;
|
||||
SPI_SendData(SPIx, data);
|
||||
// Wait for RX not empty
|
||||
while (SPI_I2S_GetFlagStatus(SPIx, SPI_I2S_FLAG_RXNE) == RESET)
|
||||
;
|
||||
return SPI_ReceiveData(SPIx);
|
||||
}
|
||||
|
||||
#endif
|
38
STM32ArduinoCompat/HardwareSPI.h
Normal file
38
STM32ArduinoCompat/HardwareSPI.h
Normal file
@@ -0,0 +1,38 @@
|
||||
// ArduinoCompat/HardwareSPI.h
|
||||
// STM32 implementattion of Arduino compatible SPI class
|
||||
|
||||
#ifndef _HardwareSPI_h
|
||||
#define _HardwareSPI_h
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
typedef enum SPIFrequency {
|
||||
SPI_21_0MHZ = 0, /**< 21 MHz */
|
||||
SPI_10_5MHZ = 1, /**< 10.5 MHz */
|
||||
SPI_5_25MHZ = 2, /**< 5.25 MHz */
|
||||
SPI_2_625MHZ = 3, /**< 2.625 MHz */
|
||||
SPI_1_3125MHZ = 4, /**< 1.3125 MHz */
|
||||
SPI_656_25KHZ = 5, /**< 656.25 KHz */
|
||||
SPI_328_125KHZ = 6, /**< 328.125 KHz */
|
||||
} SPIFrequency;
|
||||
|
||||
#define SPI_MODE0 0x00
|
||||
#define SPI_MODE1 0x04
|
||||
#define SPI_MODE2 0x08
|
||||
#define SPI_MODE3 0x0C
|
||||
|
||||
class HardwareSPI
|
||||
{
|
||||
public:
|
||||
HardwareSPI(uint32_t spiPortNumber); // Only port SPI1 is currently supported
|
||||
void begin(SPIFrequency frequency, uint32_t bitOrder, uint32_t mode);
|
||||
void end(void);
|
||||
uint8_t transfer(uint8_t data);
|
||||
|
||||
private:
|
||||
uint32_t _spiPortNumber; // Not used yet.
|
||||
};
|
||||
extern HardwareSPI SPI;
|
||||
|
||||
|
||||
#endif
|
349
STM32ArduinoCompat/HardwareSerial.cpp
Normal file
349
STM32ArduinoCompat/HardwareSerial.cpp
Normal file
@@ -0,0 +1,349 @@
|
||||
// ArduinoCompat/HardwareSerial.cpp
|
||||
//
|
||||
// Author: mikem@airspayce.com
|
||||
|
||||
#include <RadioHead.h>
|
||||
#if (RH_PLATFORM == RH_PLATFORM_STM32STD)
|
||||
#include <HardwareSerial.h>
|
||||
#include <stm32f4xx_usart.h>
|
||||
|
||||
// Preinstantiated Serial objects
|
||||
HardwareSerial Serial1(USART1);
|
||||
HardwareSerial Serial2(USART2);
|
||||
HardwareSerial Serial3(USART3);
|
||||
HardwareSerial Serial4(UART4);
|
||||
HardwareSerial Serial5(UART5);
|
||||
HardwareSerial Serial6(USART6);
|
||||
|
||||
///////////////////////////////////////////////////////////////
|
||||
// RingBuffer
|
||||
///////////////////////////////////////////////////////////////
|
||||
|
||||
RingBuffer::RingBuffer()
|
||||
: _head(0),
|
||||
_tail(0),
|
||||
_overruns(0),
|
||||
_underruns(0)
|
||||
{
|
||||
}
|
||||
|
||||
bool RingBuffer::isEmpty()
|
||||
{
|
||||
return _head == _tail;
|
||||
}
|
||||
|
||||
bool RingBuffer::isFull()
|
||||
{
|
||||
return ((_head + 1) % ARDUINO_RINGBUFFER_SIZE) == _tail;
|
||||
}
|
||||
|
||||
bool RingBuffer::write(uint8_t ch)
|
||||
{
|
||||
if (isFull())
|
||||
{
|
||||
_overruns++;
|
||||
return false;
|
||||
}
|
||||
_buffer[_head] = ch;
|
||||
if (++_head >= ARDUINO_RINGBUFFER_SIZE)
|
||||
_head = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
uint8_t RingBuffer::read()
|
||||
{
|
||||
if (isEmpty())
|
||||
{
|
||||
_underruns++;
|
||||
return 0; // What else can we do?
|
||||
}
|
||||
uint8_t ret = _buffer[_tail];
|
||||
if (++_tail >= ARDUINO_RINGBUFFER_SIZE)
|
||||
_tail = 0;
|
||||
return ret;
|
||||
}
|
||||
|
||||
///////////////////////////////////////////////////////////////
|
||||
// HardwareSerial
|
||||
///////////////////////////////////////////////////////////////
|
||||
|
||||
// On STM32F4 Discovery, USART 1 is not very useful conflicts with the Green lED
|
||||
HardwareSerial::HardwareSerial(USART_TypeDef* usart)
|
||||
: _usart(usart)
|
||||
{
|
||||
}
|
||||
|
||||
void HardwareSerial::begin(unsigned long baud)
|
||||
{
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
GPIO_InitTypeDef GPIO_InitStructure_TX;
|
||||
GPIO_InitTypeDef GPIO_InitStructure_RX;
|
||||
|
||||
// Common GPIO structure init:
|
||||
GPIO_InitStructure_TX.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure_TX.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure_TX.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure_TX.GPIO_PuPd = GPIO_PuPd_UP;
|
||||
|
||||
GPIO_InitStructure_RX.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure_RX.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure_RX.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure_RX.GPIO_PuPd = GPIO_PuPd_UP;
|
||||
// CTS or SCLK outputs are not supported.
|
||||
|
||||
USART_InitStructure.USART_BaudRate = baud * 25/8; // Why?
|
||||
// Only 8N1 is currently supported
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
||||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
|
||||
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
||||
|
||||
// Different for each USART:
|
||||
if (_usart == USART1)
|
||||
{
|
||||
// Initialise the clocks for this USART and its RX, TX pins port
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
|
||||
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
|
||||
|
||||
GPIO_PinAFConfig(GPIOA, GPIO_PinSource9, GPIO_AF_USART1);
|
||||
GPIO_PinAFConfig(GPIOA, GPIO_PinSource10, GPIO_AF_USART1);
|
||||
|
||||
GPIO_InitStructure_TX.GPIO_Pin = GPIO_Pin_9;
|
||||
GPIO_InitStructure_RX.GPIO_Pin = GPIO_Pin_10;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure_TX);
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure_RX);
|
||||
// Initialise the USART
|
||||
USART_Init(USART1, &USART_InitStructure);
|
||||
// Enable the RXNE interrupt
|
||||
USART_ITConfig(USART1, USART_IT_RXNE, ENABLE);
|
||||
// Enable global interrupt
|
||||
NVIC_EnableIRQ(USART1_IRQn);
|
||||
}
|
||||
else if (_usart == USART2)
|
||||
{
|
||||
// Initialise the clocks for this USART and its RX, TX pins port
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
|
||||
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
|
||||
|
||||
GPIO_PinAFConfig(GPIOA, GPIO_PinSource2, GPIO_AF_USART2);
|
||||
GPIO_PinAFConfig(GPIOA, GPIO_PinSource3, GPIO_AF_USART2);
|
||||
|
||||
GPIO_InitStructure_TX.GPIO_Pin = GPIO_Pin_2;
|
||||
GPIO_InitStructure_RX.GPIO_Pin = GPIO_Pin_3;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure_TX);
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure_RX);
|
||||
// Initialise the USART
|
||||
USART_Init(USART2, &USART_InitStructure);
|
||||
// Enable the RXNE interrupt
|
||||
USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);
|
||||
// Enable global interrupt
|
||||
NVIC_EnableIRQ(USART2_IRQn);
|
||||
}
|
||||
else if (_usart == USART3)
|
||||
{
|
||||
// Initialise the clocks for this USART and its RX, TX pins port
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
|
||||
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD, ENABLE);
|
||||
|
||||
GPIO_PinAFConfig(GPIOD, GPIO_PinSource8, GPIO_AF_USART3);
|
||||
GPIO_PinAFConfig(GPIOD, GPIO_PinSource9, GPIO_AF_USART3);
|
||||
|
||||
GPIO_InitStructure_TX.GPIO_Pin = GPIO_Pin_8;
|
||||
GPIO_InitStructure_RX.GPIO_Pin = GPIO_Pin_9;
|
||||
GPIO_Init(GPIOD, &GPIO_InitStructure_TX);
|
||||
GPIO_Init(GPIOD, &GPIO_InitStructure_RX);
|
||||
// Initialise the USART
|
||||
USART_Init(USART3, &USART_InitStructure);
|
||||
// Enable the RXNE interrupt
|
||||
USART_ITConfig(USART3, USART_IT_RXNE, ENABLE);
|
||||
// Enable global interrupt
|
||||
NVIC_EnableIRQ(USART3_IRQn);
|
||||
}
|
||||
else if (_usart == UART4)
|
||||
{
|
||||
// Initialise the clocks for this USART and its RX, TX pins port
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART4, ENABLE);
|
||||
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
|
||||
|
||||
GPIO_PinAFConfig(GPIOA, GPIO_PinSource0, GPIO_AF_UART4);
|
||||
GPIO_PinAFConfig(GPIOA, GPIO_PinSource1, GPIO_AF_UART4);
|
||||
|
||||
GPIO_InitStructure_TX.GPIO_Pin = GPIO_Pin_0;
|
||||
GPIO_InitStructure_RX.GPIO_Pin = GPIO_Pin_1;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure_TX);
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure_RX);
|
||||
// Initialise the USART
|
||||
USART_Init(UART4, &USART_InitStructure);
|
||||
// Enable the RXNE interrupt
|
||||
USART_ITConfig(UART4, USART_IT_RXNE, ENABLE);
|
||||
// Enable global interrupt
|
||||
NVIC_EnableIRQ(UART4_IRQn);
|
||||
}
|
||||
else if (_usart == UART5)
|
||||
{
|
||||
// Initialise the clocks for this USART and its RX, TX pins port
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART5, ENABLE);
|
||||
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC | RCC_AHB1Periph_GPIOD, ENABLE);
|
||||
|
||||
GPIO_PinAFConfig(GPIOC, GPIO_PinSource12, GPIO_AF_UART5);
|
||||
GPIO_PinAFConfig(GPIOD, GPIO_PinSource2, GPIO_AF_UART5);
|
||||
|
||||
GPIO_InitStructure_TX.GPIO_Pin = GPIO_Pin_12;
|
||||
GPIO_InitStructure_RX.GPIO_Pin = GPIO_Pin_2;
|
||||
GPIO_Init(GPIOC, &GPIO_InitStructure_TX);
|
||||
GPIO_Init(GPIOD, &GPIO_InitStructure_RX);
|
||||
// Initialise the USART
|
||||
USART_Init(UART5, &USART_InitStructure);
|
||||
// Enable the RXNE interrupt
|
||||
USART_ITConfig(UART5, USART_IT_RXNE, ENABLE);
|
||||
// Enable global interrupt
|
||||
NVIC_EnableIRQ(UART5_IRQn);
|
||||
}
|
||||
else if (_usart == USART6)
|
||||
{
|
||||
// Initialise the clocks for this USART and its RX, TX pins port
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART6, ENABLE);
|
||||
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
|
||||
|
||||
GPIO_PinAFConfig(GPIOC, GPIO_PinSource6, GPIO_AF_USART6);
|
||||
GPIO_PinAFConfig(GPIOC, GPIO_PinSource7, GPIO_AF_USART6);
|
||||
|
||||
GPIO_InitStructure_TX.GPIO_Pin = GPIO_Pin_6;
|
||||
GPIO_InitStructure_RX.GPIO_Pin = GPIO_Pin_7;
|
||||
GPIO_Init(GPIOC, &GPIO_InitStructure_TX);
|
||||
GPIO_Init(GPIOC, &GPIO_InitStructure_RX);
|
||||
// Initialise the USART
|
||||
USART_Init(USART6, &USART_InitStructure);
|
||||
// Enable the RXNE interrupt
|
||||
USART_ITConfig(USART6, USART_IT_RXNE, ENABLE);
|
||||
// Enable global interrupt
|
||||
NVIC_EnableIRQ(USART6_IRQn);
|
||||
}
|
||||
|
||||
USART_Cmd(_usart, ENABLE);
|
||||
}
|
||||
|
||||
void HardwareSerial::end()
|
||||
{
|
||||
USART_Cmd(_usart, DISABLE);
|
||||
USART_DeInit(_usart);
|
||||
}
|
||||
|
||||
int HardwareSerial::available(void)
|
||||
{
|
||||
return !_rxRingBuffer.isEmpty();
|
||||
}
|
||||
|
||||
int HardwareSerial::read(void)
|
||||
{
|
||||
return _rxRingBuffer.read();
|
||||
}
|
||||
|
||||
size_t HardwareSerial::write(uint8_t ch)
|
||||
{
|
||||
_txRingBuffer.write(ch); // Queue it
|
||||
USART_ITConfig(_usart, USART_IT_TXE, ENABLE); // Enable the TX interrupt
|
||||
return 1;
|
||||
}
|
||||
|
||||
extern "C"
|
||||
{
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
if (USART_GetITStatus(USART1, USART_IT_RXNE) != RESET)
|
||||
{
|
||||
Serial1._rxRingBuffer.write(USART_ReceiveData(USART1));
|
||||
}
|
||||
if (USART_GetITStatus(USART1, USART_IT_TXE) != RESET)
|
||||
{
|
||||
// Transmitter is empty, maybe send another char?
|
||||
if (Serial1._txRingBuffer.isEmpty())
|
||||
USART_ITConfig(USART1, USART_IT_TXE, DISABLE); // No more to send, disable the TX interrupt
|
||||
else
|
||||
USART_SendData(USART1, Serial1._txRingBuffer.read());
|
||||
}
|
||||
}
|
||||
void USART2_IRQHandler(void)
|
||||
{
|
||||
if (USART_GetITStatus(USART2, USART_IT_RXNE) != RESET)
|
||||
{
|
||||
// Newly received char, try to put it in our rx buffer
|
||||
Serial2._rxRingBuffer.write(USART_ReceiveData(USART2));
|
||||
}
|
||||
if (USART_GetITStatus(USART2, USART_IT_TXE) != RESET)
|
||||
{
|
||||
// Transmitter is empty, maybe send another char?
|
||||
if (Serial2._txRingBuffer.isEmpty())
|
||||
USART_ITConfig(USART2, USART_IT_TXE, DISABLE); // No more to send, disable the TX interrupt
|
||||
else
|
||||
USART_SendData(USART2, Serial2._txRingBuffer.read());
|
||||
}
|
||||
}
|
||||
void USART3_IRQHandler(void)
|
||||
{
|
||||
if (USART_GetITStatus(USART3, USART_IT_RXNE) != RESET)
|
||||
{
|
||||
// Newly received char, try to put it in our rx buffer
|
||||
Serial3._rxRingBuffer.write(USART_ReceiveData(USART3));
|
||||
}
|
||||
if (USART_GetITStatus(USART3, USART_IT_TXE) != RESET)
|
||||
{
|
||||
// Transmitter is empty, maybe send another char?
|
||||
if (Serial3._txRingBuffer.isEmpty())
|
||||
USART_ITConfig(USART3, USART_IT_TXE, DISABLE); // No more to send, disable the TX interrupt
|
||||
else
|
||||
USART_SendData(USART3, Serial3._txRingBuffer.read());
|
||||
}
|
||||
}
|
||||
void UART4_IRQHandler(void)
|
||||
{
|
||||
if (USART_GetITStatus(UART4, USART_IT_RXNE) != RESET)
|
||||
{
|
||||
// Newly received char, try to put it in our rx buffer
|
||||
Serial4._rxRingBuffer.write(USART_ReceiveData(UART4));
|
||||
}
|
||||
if (USART_GetITStatus(UART4, USART_IT_TXE) != RESET)
|
||||
{
|
||||
// Transmitter is empty, maybe send another char?
|
||||
if (Serial4._txRingBuffer.isEmpty())
|
||||
USART_ITConfig(UART4, USART_IT_TXE, DISABLE); // No more to send, disable the TX interrupt
|
||||
else
|
||||
USART_SendData(UART4, Serial4._txRingBuffer.read());
|
||||
}
|
||||
}
|
||||
void UART5_IRQHandler(void)
|
||||
{
|
||||
if (USART_GetITStatus(UART5, USART_IT_RXNE) != RESET)
|
||||
{
|
||||
// Newly received char, try to put it in our rx buffer
|
||||
Serial5._rxRingBuffer.write(USART_ReceiveData(UART5));
|
||||
}
|
||||
if (USART_GetITStatus(UART5, USART_IT_TXE) != RESET)
|
||||
{
|
||||
// Transmitter is empty, maybe send another char?
|
||||
if (Serial5._txRingBuffer.isEmpty())
|
||||
USART_ITConfig(UART5, USART_IT_TXE, DISABLE); // No more to send, disable the TX interrupt
|
||||
else
|
||||
USART_SendData(UART5, Serial5._txRingBuffer.read());
|
||||
}
|
||||
}
|
||||
void USART6_IRQHandler(void)
|
||||
{
|
||||
if (USART_GetITStatus(USART6, USART_IT_RXNE) != RESET)
|
||||
{
|
||||
// Newly received char, try to put it in our rx buffer
|
||||
Serial6._rxRingBuffer.write(USART_ReceiveData(USART6));
|
||||
}
|
||||
if (USART_GetITStatus(USART6, USART_IT_TXE) != RESET)
|
||||
{
|
||||
// Transmitter is empty, maybe send another char?
|
||||
if (Serial6._txRingBuffer.isEmpty())
|
||||
USART_ITConfig(USART6, USART_IT_TXE, DISABLE); // No more to send, disable the TX interrupt
|
||||
else
|
||||
USART_SendData(USART6, Serial6._txRingBuffer.read());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
78
STM32ArduinoCompat/HardwareSerial.h
Normal file
78
STM32ArduinoCompat/HardwareSerial.h
Normal file
@@ -0,0 +1,78 @@
|
||||
// ArduinoCompat/HardwareSerial.h
|
||||
// STM32 implementation of Arduino compatible serial class
|
||||
|
||||
#include <RadioHead.h>
|
||||
#if (RH_PLATFORM == RH_PLATFORM_STM32STD)
|
||||
#ifndef _HardwareSerial_h
|
||||
#define _HardwareSerial_h
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <stm32f4xx.h>
|
||||
|
||||
#ifndef ARDUINO_RINGBUFFER_SIZE
|
||||
#define ARDUINO_RINGBUFFER_SIZE 64
|
||||
#endif
|
||||
|
||||
class RingBuffer
|
||||
{
|
||||
public:
|
||||
RingBuffer();
|
||||
bool isEmpty();
|
||||
bool isFull();
|
||||
bool write(uint8_t ch);
|
||||
uint8_t read();
|
||||
|
||||
private:
|
||||
uint8_t _buffer[ARDUINO_RINGBUFFER_SIZE]; // In fact we can hold up to ARDUINO_RINGBUFFER_SIZE-1 bytes
|
||||
uint16_t _head; // Index of next write
|
||||
uint16_t _tail; // Index of next read
|
||||
uint32_t _overruns; // Write attempted when buffer full
|
||||
uint32_t _underruns; // Read attempted when buffer empty
|
||||
};
|
||||
|
||||
// Mostly compatible wuith Arduino HardwareSerial
|
||||
// Theres just enough here to support RadioHead RH_Serial
|
||||
class HardwareSerial
|
||||
{
|
||||
public:
|
||||
HardwareSerial(USART_TypeDef* usart);
|
||||
void begin(unsigned long baud);
|
||||
void end();
|
||||
virtual int available(void);
|
||||
virtual int read(void);
|
||||
virtual size_t write(uint8_t);
|
||||
inline size_t write(unsigned long n) { return write((uint8_t)n); }
|
||||
inline size_t write(long n) { return write((uint8_t)n); }
|
||||
inline size_t write(unsigned int n) { return write((uint8_t)n); }
|
||||
inline size_t write(int n) { return write((uint8_t)n); }
|
||||
|
||||
// These need to be public so the IRQ handler can read and write to them:
|
||||
RingBuffer _rxRingBuffer;
|
||||
RingBuffer _txRingBuffer;
|
||||
|
||||
private:
|
||||
USART_TypeDef* _usart;
|
||||
|
||||
};
|
||||
|
||||
// Predefined serial ports are configured so:
|
||||
// Serial STM32 UART RX pin Tx Pin Comments
|
||||
// Serial1 USART1 PA10 PA9 TX Conflicts with GREEN LED on Discovery
|
||||
// Serial2 USART2 PA3 PA2
|
||||
// Serial3 USART3 PD9 PD10
|
||||
// Serial4 UART4 PA1 PA0 TX conflicts with USER button on Discovery
|
||||
// Serial5 UART5 PD2 PC12 TX conflicts with CS43L22 SDIN on Discovery
|
||||
// Serial6 USART6 PC7 PC6 RX conflicts with CS43L22 MCLK on Discovery
|
||||
//
|
||||
// All ports are idle HIGH, LSB first, 8 bits, No parity, 1 stop bit
|
||||
extern HardwareSerial Serial1;
|
||||
extern HardwareSerial Serial2;
|
||||
extern HardwareSerial Serial3;
|
||||
extern HardwareSerial Serial4;
|
||||
extern HardwareSerial Serial5;
|
||||
extern HardwareSerial Serial6;
|
||||
|
||||
#endif
|
||||
|
||||
#endif
|
6
STM32ArduinoCompat/README
Normal file
6
STM32ArduinoCompat/README
Normal file
@@ -0,0 +1,6 @@
|
||||
This directory contains some files to allow RadioHead to be built on STM32F4
|
||||
Discovery boards, using the native STM Firmware libraries, in order to support
|
||||
Codec2WalkieTalkie and other projects.
|
||||
|
||||
The files provide just enough Arduino compatibility to allow RadioHead to
|
||||
build in that environment.
|
413
STM32ArduinoCompat/wirish.cpp
Normal file
413
STM32ArduinoCompat/wirish.cpp
Normal file
@@ -0,0 +1,413 @@
|
||||
// ArduinoCompat/wirish.cpp
|
||||
//
|
||||
// Arduino-like API for STM32F4 Discovery and similar
|
||||
// using STM32F4xx_DSP_StdPeriph_Lib_V1.3.0
|
||||
|
||||
#include <RadioHead.h>
|
||||
#if (RH_PLATFORM == RH_PLATFORM_STM32STD)
|
||||
#include <wirish.h>
|
||||
|
||||
SerialUSBClass SerialUSB;
|
||||
|
||||
// Describes all the STM32 things we need to know about a digital IO pin to
|
||||
// make it input or output or to configure as an interrupt
|
||||
typedef struct
|
||||
{
|
||||
uint32_t ahbperiph;
|
||||
GPIO_TypeDef* port;
|
||||
uint16_t pin;
|
||||
uint8_t extiportsource;
|
||||
uint8_t extipinsource;
|
||||
} GPIOPin;
|
||||
|
||||
// These describe the registers and bits for each digital IO pin to allow us to
|
||||
// provide Arduino-like pin addressing, digitalRead etc.
|
||||
// Indexed by pin number
|
||||
GPIOPin pins[] =
|
||||
{
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_0, EXTI_PortSourceGPIOA, EXTI_PinSource0 }, // 0 = PA0
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_1, EXTI_PortSourceGPIOA, EXTI_PinSource1 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_2, EXTI_PortSourceGPIOA, EXTI_PinSource2 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_3, EXTI_PortSourceGPIOA, EXTI_PinSource3 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_4, EXTI_PortSourceGPIOA, EXTI_PinSource4 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_5, EXTI_PortSourceGPIOA, EXTI_PinSource5 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_6, EXTI_PortSourceGPIOA, EXTI_PinSource6 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_7, EXTI_PortSourceGPIOA, EXTI_PinSource7 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_8, EXTI_PortSourceGPIOA, EXTI_PinSource8 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_9, EXTI_PortSourceGPIOA, EXTI_PinSource9 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_10, EXTI_PortSourceGPIOA, EXTI_PinSource10 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_11, EXTI_PortSourceGPIOA, EXTI_PinSource11 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_12, EXTI_PortSourceGPIOA, EXTI_PinSource12 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_13, EXTI_PortSourceGPIOA, EXTI_PinSource13 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_14, EXTI_PortSourceGPIOA, EXTI_PinSource14 },
|
||||
{ RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_15, EXTI_PortSourceGPIOA, EXTI_PinSource15 }, // 15 = PA15
|
||||
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_0, EXTI_PortSourceGPIOB, EXTI_PinSource0 }, // 16 = PB0
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_1, EXTI_PortSourceGPIOB, EXTI_PinSource1 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_2, EXTI_PortSourceGPIOB, EXTI_PinSource2 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_3, EXTI_PortSourceGPIOB, EXTI_PinSource3 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_4, EXTI_PortSourceGPIOB, EXTI_PinSource4 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_5, EXTI_PortSourceGPIOB, EXTI_PinSource5 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_6, EXTI_PortSourceGPIOB, EXTI_PinSource6 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_7, EXTI_PortSourceGPIOB, EXTI_PinSource7 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_8, EXTI_PortSourceGPIOB, EXTI_PinSource8 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_9, EXTI_PortSourceGPIOB, EXTI_PinSource9 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_10, EXTI_PortSourceGPIOB, EXTI_PinSource10 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_11, EXTI_PortSourceGPIOB, EXTI_PinSource11 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_12, EXTI_PortSourceGPIOB, EXTI_PinSource12 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_13, EXTI_PortSourceGPIOB, EXTI_PinSource13 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_14, EXTI_PortSourceGPIOB, EXTI_PinSource14 },
|
||||
{ RCC_AHB1Periph_GPIOB, GPIOB, GPIO_Pin_15, EXTI_PortSourceGPIOB, EXTI_PinSource15 }, // 31 = PB15
|
||||
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_0, EXTI_PortSourceGPIOC, EXTI_PinSource0 }, // 32 = PC0
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_1, EXTI_PortSourceGPIOC, EXTI_PinSource1 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_2, EXTI_PortSourceGPIOC, EXTI_PinSource2 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_3, EXTI_PortSourceGPIOC, EXTI_PinSource3 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_4, EXTI_PortSourceGPIOC, EXTI_PinSource4 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_5, EXTI_PortSourceGPIOC, EXTI_PinSource5 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_6, EXTI_PortSourceGPIOC, EXTI_PinSource6 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_7, EXTI_PortSourceGPIOC, EXTI_PinSource7 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_8, EXTI_PortSourceGPIOC, EXTI_PinSource8 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_9, EXTI_PortSourceGPIOC, EXTI_PinSource9 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_10, EXTI_PortSourceGPIOC, EXTI_PinSource10 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_11, EXTI_PortSourceGPIOC, EXTI_PinSource11 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_12, EXTI_PortSourceGPIOC, EXTI_PinSource12 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_13, EXTI_PortSourceGPIOC, EXTI_PinSource13 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_14, EXTI_PortSourceGPIOC, EXTI_PinSource14 },
|
||||
{ RCC_AHB1Periph_GPIOC, GPIOC, GPIO_Pin_15, EXTI_PortSourceGPIOC, EXTI_PinSource15 }, // 47 = PC15
|
||||
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_0, EXTI_PortSourceGPIOD, EXTI_PinSource0 }, // 48 = PD0
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_1, EXTI_PortSourceGPIOD, EXTI_PinSource1 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_2, EXTI_PortSourceGPIOD, EXTI_PinSource2 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_3, EXTI_PortSourceGPIOD, EXTI_PinSource3 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_4, EXTI_PortSourceGPIOD, EXTI_PinSource4 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_5, EXTI_PortSourceGPIOD, EXTI_PinSource5 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_6, EXTI_PortSourceGPIOD, EXTI_PinSource6 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_7, EXTI_PortSourceGPIOD, EXTI_PinSource7 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_8, EXTI_PortSourceGPIOD, EXTI_PinSource8 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_9, EXTI_PortSourceGPIOD, EXTI_PinSource9 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_10, EXTI_PortSourceGPIOD, EXTI_PinSource10 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_11, EXTI_PortSourceGPIOD, EXTI_PinSource11 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_12, EXTI_PortSourceGPIOD, EXTI_PinSource12 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_13, EXTI_PortSourceGPIOD, EXTI_PinSource13 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_14, EXTI_PortSourceGPIOD, EXTI_PinSource14 },
|
||||
{ RCC_AHB1Periph_GPIOD, GPIOD, GPIO_Pin_15, EXTI_PortSourceGPIOD, EXTI_PinSource15 }, // 63 = PD15
|
||||
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_0, EXTI_PortSourceGPIOE, EXTI_PinSource0 }, // 64 = PE0
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_1, EXTI_PortSourceGPIOE, EXTI_PinSource1 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_2, EXTI_PortSourceGPIOE, EXTI_PinSource2 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_3, EXTI_PortSourceGPIOE, EXTI_PinSource3 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_4, EXTI_PortSourceGPIOE, EXTI_PinSource4 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_5, EXTI_PortSourceGPIOE, EXTI_PinSource5 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_6, EXTI_PortSourceGPIOE, EXTI_PinSource6 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_7, EXTI_PortSourceGPIOE, EXTI_PinSource7 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_8, EXTI_PortSourceGPIOE, EXTI_PinSource8 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_9, EXTI_PortSourceGPIOE, EXTI_PinSource9 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_10, EXTI_PortSourceGPIOE, EXTI_PinSource10 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_11, EXTI_PortSourceGPIOE, EXTI_PinSource11 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_12, EXTI_PortSourceGPIOE, EXTI_PinSource12 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_13, EXTI_PortSourceGPIOE, EXTI_PinSource13 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_14, EXTI_PortSourceGPIOE, EXTI_PinSource14 },
|
||||
{ RCC_AHB1Periph_GPIOE, GPIOE, GPIO_Pin_15, EXTI_PortSourceGPIOE, EXTI_PinSource15 }, // 79 = PE15
|
||||
|
||||
};
|
||||
#define NUM_PINS (sizeof(pins) / sizeof(GPIOPin))
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t extiline;
|
||||
uint8_t extiirqn;
|
||||
void (*handler)(void);
|
||||
} IRQLine;
|
||||
|
||||
// IRQ line data indexed by pin source number with its port
|
||||
// and the programmable handler that will handle interrupts on that line
|
||||
IRQLine irqlines[] =
|
||||
{
|
||||
{ EXTI_Line0, EXTI0_IRQn, 0 },
|
||||
{ EXTI_Line1, EXTI1_IRQn, 0 },
|
||||
{ EXTI_Line2, EXTI2_IRQn, 0 },
|
||||
{ EXTI_Line3, EXTI3_IRQn, 0 },
|
||||
{ EXTI_Line4, EXTI4_IRQn, 0 },
|
||||
{ EXTI_Line5, EXTI9_5_IRQn, 0 },
|
||||
{ EXTI_Line6, EXTI9_5_IRQn, 0 },
|
||||
{ EXTI_Line7, EXTI9_5_IRQn, 0 },
|
||||
{ EXTI_Line8, EXTI9_5_IRQn, 0 },
|
||||
{ EXTI_Line9, EXTI9_5_IRQn, 0 },
|
||||
{ EXTI_Line10, EXTI15_10_IRQn, 0 },
|
||||
{ EXTI_Line11, EXTI15_10_IRQn, 0 },
|
||||
{ EXTI_Line12, EXTI15_10_IRQn, 0 },
|
||||
{ EXTI_Line13, EXTI15_10_IRQn, 0 },
|
||||
{ EXTI_Line14, EXTI15_10_IRQn, 0 },
|
||||
{ EXTI_Line15, EXTI15_10_IRQn, 0 },
|
||||
};
|
||||
|
||||
#define NUM_IRQ_LINES (sizeof(irqlines) / sizeof(IRQLine))
|
||||
|
||||
// Functions we expect to find in the sketch
|
||||
extern void setup();
|
||||
extern void loop();
|
||||
|
||||
volatile unsigned long systick_count = 0;
|
||||
|
||||
void SysTickConfig()
|
||||
{
|
||||
/* Setup SysTick Timer for 1ms interrupts */
|
||||
if (SysTick_Config(SystemCoreClock / 1000))
|
||||
{
|
||||
/* Capture error */
|
||||
while (1);
|
||||
}
|
||||
|
||||
/* Configure the SysTick handler priority */
|
||||
NVIC_SetPriority(SysTick_IRQn, 0x0);
|
||||
// SysTick_Handler will now be called every 1 ms
|
||||
}
|
||||
|
||||
// These interrupt handlers have to be extern C else they dont get linked in to the interrupt vectors
|
||||
extern "C"
|
||||
{
|
||||
// Called every 1 ms
|
||||
void SysTick_Handler(void)
|
||||
{
|
||||
systick_count++;
|
||||
}
|
||||
|
||||
// Interrupt handlers for optional external GPIO interrupts
|
||||
void EXTI0_IRQHandler(void)
|
||||
{
|
||||
if (EXTI_GetITStatus(EXTI_Line0) != RESET)
|
||||
{
|
||||
if (irqlines[0].handler)
|
||||
irqlines[0].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line0);
|
||||
}
|
||||
}
|
||||
void EXTI1_IRQHandler(void)
|
||||
{
|
||||
if (EXTI_GetITStatus(EXTI_Line1) != RESET)
|
||||
{
|
||||
if (irqlines[1].handler)
|
||||
irqlines[1].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line1);
|
||||
}
|
||||
}
|
||||
void EXTI2_IRQHandler(void)
|
||||
{
|
||||
if (EXTI_GetITStatus(EXTI_Line2) != RESET)
|
||||
{
|
||||
if (irqlines[2].handler)
|
||||
irqlines[2].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line2);
|
||||
}
|
||||
}
|
||||
void EXTI3_IRQHandler(void)
|
||||
{
|
||||
if (EXTI_GetITStatus(EXTI_Line3) != RESET)
|
||||
{
|
||||
if (irqlines[3].handler)
|
||||
irqlines[3].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line3);
|
||||
}
|
||||
}
|
||||
void EXTI4_IRQHandler(void)
|
||||
{
|
||||
if (EXTI_GetITStatus(EXTI_Line4) != RESET)
|
||||
{
|
||||
if (irqlines[4].handler)
|
||||
irqlines[4].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line4);
|
||||
}
|
||||
}
|
||||
void EXTI9_5_IRQHandler(void)
|
||||
{
|
||||
if (EXTI_GetITStatus(EXTI_Line5) != RESET)
|
||||
{
|
||||
if (irqlines[5].handler)
|
||||
irqlines[5].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line5);
|
||||
}
|
||||
if (EXTI_GetITStatus(EXTI_Line6) != RESET)
|
||||
{
|
||||
if (irqlines[6].handler)
|
||||
irqlines[6].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line6);
|
||||
}
|
||||
if (EXTI_GetITStatus(EXTI_Line7) != RESET)
|
||||
{
|
||||
if (irqlines[7].handler)
|
||||
irqlines[7].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line7);
|
||||
}
|
||||
if (EXTI_GetITStatus(EXTI_Line8) != RESET)
|
||||
{
|
||||
if (irqlines[8].handler)
|
||||
irqlines[8].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line8);
|
||||
}
|
||||
if (EXTI_GetITStatus(EXTI_Line9) != RESET)
|
||||
{
|
||||
if (irqlines[9].handler)
|
||||
irqlines[9].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line9);
|
||||
}
|
||||
}
|
||||
void EXTI15_10_IRQHandler(void)
|
||||
{
|
||||
if (EXTI_GetITStatus(EXTI_Line10) != RESET)
|
||||
{
|
||||
if (irqlines[10].handler)
|
||||
irqlines[10].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line10);
|
||||
}
|
||||
if (EXTI_GetITStatus(EXTI_Line11) != RESET)
|
||||
{
|
||||
if (irqlines[11].handler)
|
||||
irqlines[11].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line11);
|
||||
}
|
||||
if (EXTI_GetITStatus(EXTI_Line12) != RESET)
|
||||
{
|
||||
if (irqlines[12].handler)
|
||||
irqlines[12].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line12);
|
||||
}
|
||||
if (EXTI_GetITStatus(EXTI_Line13) != RESET)
|
||||
{
|
||||
if (irqlines[13].handler)
|
||||
irqlines[13].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line13);
|
||||
}
|
||||
if (EXTI_GetITStatus(EXTI_Line14) != RESET)
|
||||
{
|
||||
if (irqlines[14].handler)
|
||||
irqlines[14].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line14);
|
||||
}
|
||||
if (EXTI_GetITStatus(EXTI_Line15) != RESET)
|
||||
{
|
||||
if (irqlines[15].handler)
|
||||
irqlines[15].handler();
|
||||
EXTI_ClearITPendingBit(EXTI_Line15);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// The sketch we want to run
|
||||
//#include "examples/rf22/rf22_client/rf22_client.pde"
|
||||
|
||||
// Run the Arduino standard functions in the main loop
|
||||
int main(int argc, char** argv)
|
||||
{
|
||||
SysTickConfig();
|
||||
// Seed the random number generator
|
||||
// srand(getpid() ^ (unsigned) time(NULL)/2);
|
||||
setup();
|
||||
while (1)
|
||||
loop();
|
||||
}
|
||||
|
||||
void pinMode(uint8_t pin, WiringPinMode mode)
|
||||
{
|
||||
if (pin > NUM_PINS)
|
||||
return;
|
||||
// Enable the GPIO clock
|
||||
RCC_AHB1PeriphClockCmd(pins[pin].ahbperiph, ENABLE);
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_InitStructure.GPIO_Pin = pins[pin].pin;
|
||||
if (mode == INPUT)
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN; // REVISIT
|
||||
else if (mode == OUTPUT)
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; // REVISIT
|
||||
else
|
||||
return; // Unknown so far
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_Init(pins[pin].port, &GPIO_InitStructure);
|
||||
}
|
||||
|
||||
// This takes about 150ns on STM32F4 Discovery
|
||||
void digitalWrite(uint8_t pin, uint8_t val)
|
||||
{
|
||||
if (pin > NUM_PINS)
|
||||
return;
|
||||
if (val)
|
||||
GPIO_SetBits(pins[pin].port, pins[pin].pin);
|
||||
else
|
||||
GPIO_ResetBits(pins[pin].port, pins[pin].pin);
|
||||
}
|
||||
|
||||
uint8_t digitalRead(uint8_t pin)
|
||||
{
|
||||
if (pin > NUM_PINS)
|
||||
return 0;
|
||||
return GPIO_ReadInputDataBit(pins[pin].port, pins[pin].pin);
|
||||
}
|
||||
|
||||
void attachInterrupt(uint8_t pin, void (*handler)(void), int mode)
|
||||
{
|
||||
EXTI_InitTypeDef EXTI_InitStructure;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
// Record the handler to call when the interrupt occurs
|
||||
irqlines[pins[pin].extipinsource].handler = handler;
|
||||
|
||||
/* Connect EXTI Line to GPIO Pin */
|
||||
SYSCFG_EXTILineConfig(pins[pin].extiportsource, pins[pin].extipinsource);
|
||||
|
||||
/* Configure EXTI line */
|
||||
EXTI_InitStructure.EXTI_Line = irqlines[pins[pin].extipinsource].extiline;
|
||||
|
||||
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
|
||||
if (mode == RISING)
|
||||
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
|
||||
else if (mode == FALLING)
|
||||
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
|
||||
else if (mode == CHANGE)
|
||||
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising_Falling;
|
||||
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
|
||||
EXTI_Init(&EXTI_InitStructure);
|
||||
|
||||
/* Enable and set EXTI Interrupt to the lowest priority */
|
||||
NVIC_InitStructure.NVIC_IRQChannel = irqlines[pins[pin].extipinsource].extiirqn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x0F;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x0F;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
// The relevant EXTI?_IRQHandler
|
||||
// will now be called when the pin makes the selected transition
|
||||
}
|
||||
|
||||
void delay(unsigned long ms)
|
||||
{
|
||||
unsigned long start = millis();
|
||||
|
||||
while (millis() - start < ms)
|
||||
;
|
||||
}
|
||||
|
||||
unsigned long millis()
|
||||
{
|
||||
return systick_count;
|
||||
}
|
||||
|
||||
long random(long from, long to)
|
||||
{
|
||||
return from + (RNG_GetRandomNumber() % (to - from));
|
||||
}
|
||||
|
||||
long random(long to)
|
||||
{
|
||||
return random(0, to);
|
||||
}
|
||||
|
||||
extern "C"
|
||||
{
|
||||
// These need to be in C land for correct linking
|
||||
void _init() {}
|
||||
void _fini() {}
|
||||
}
|
||||
|
||||
#endif
|
157
STM32ArduinoCompat/wirish.h
Normal file
157
STM32ArduinoCompat/wirish.h
Normal file
@@ -0,0 +1,157 @@
|
||||
// ArduinoCompat/wirish.h
|
||||
|
||||
#ifndef _wirish_h
|
||||
#define _wirish_h
|
||||
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdint.h>
|
||||
#include <stm32f4xx_rng.h>
|
||||
|
||||
#define PROGMEM
|
||||
#define memcpy_P memcpy
|
||||
|
||||
typedef enum WiringPinMode {
|
||||
OUTPUT, /**< Basic digital output: when the pin is HIGH, the
|
||||
voltage is held at +3.3v (Vcc) and when it is LOW, it
|
||||
is pulled down to ground. */
|
||||
|
||||
OUTPUT_OPEN_DRAIN, /**< In open drain mode, the pin indicates
|
||||
"low" by accepting current flow to ground
|
||||
and "high" by providing increased
|
||||
impedance. An example use would be to
|
||||
connect a pin to a bus line (which is pulled
|
||||
up to a positive voltage by a separate
|
||||
supply through a large resistor). When the
|
||||
pin is high, not much current flows through
|
||||
to ground and the line stays at positive
|
||||
voltage; when the pin is low, the bus
|
||||
"drains" to ground with a small amount of
|
||||
current constantly flowing through the large
|
||||
resistor from the external supply. In this
|
||||
mode, no current is ever actually sourced
|
||||
from the pin. */
|
||||
|
||||
INPUT, /**< Basic digital input. The pin voltage is sampled; when
|
||||
it is closer to 3.3v (Vcc) the pin status is high, and
|
||||
when it is closer to 0v (ground) it is low. If no
|
||||
external circuit is pulling the pin voltage to high or
|
||||
low, it will tend to randomly oscillate and be very
|
||||
sensitive to noise (e.g., a breath of air across the pin
|
||||
might cause the state to flip). */
|
||||
|
||||
INPUT_ANALOG, /**< This is a special mode for when the pin will be
|
||||
used for analog (not digital) reads. Enables ADC
|
||||
conversion to be performed on the voltage at the
|
||||
pin. */
|
||||
|
||||
INPUT_PULLUP, /**< The state of the pin in this mode is reported
|
||||
the same way as with INPUT, but the pin voltage
|
||||
is gently "pulled up" towards +3.3v. This means
|
||||
the state will be high unless an external device
|
||||
is specifically pulling the pin down to ground,
|
||||
in which case the "gentle" pull up will not
|
||||
affect the state of the input. */
|
||||
|
||||
INPUT_PULLDOWN, /**< The state of the pin in this mode is reported
|
||||
the same way as with INPUT, but the pin voltage
|
||||
is gently "pulled down" towards 0v. This means
|
||||
the state will be low unless an external device
|
||||
is specifically pulling the pin up to 3.3v, in
|
||||
which case the "gentle" pull down will not
|
||||
affect the state of the input. */
|
||||
|
||||
INPUT_FLOATING, /**< Synonym for INPUT. */
|
||||
|
||||
PWM, /**< This is a special mode for when the pin will be used for
|
||||
PWM output (a special case of digital output). */
|
||||
|
||||
PWM_OPEN_DRAIN, /**< Like PWM, except that instead of alternating
|
||||
cycles of LOW and HIGH, the voltage on the pin
|
||||
consists of alternating cycles of LOW and
|
||||
floating (disconnected). */
|
||||
} WiringPinMode;
|
||||
|
||||
extern void pinMode(uint8_t pin, WiringPinMode mode);
|
||||
extern uint32_t millis();
|
||||
extern void delay(uint32_t millis);
|
||||
extern void attachInterrupt(uint8_t, void (*)(void), int mode);
|
||||
extern void digitalWrite(uint8_t pin, uint8_t val);
|
||||
extern uint8_t digitalRead(uint8_t pin);
|
||||
|
||||
//extern long random(long to);
|
||||
//extern long random(long from, long to);
|
||||
|
||||
#define HIGH 0x1
|
||||
#define LOW 0x0
|
||||
|
||||
#define LSBFIRST 0
|
||||
#define MSBFIRST 1
|
||||
|
||||
#define CHANGE 1
|
||||
#define FALLING 2
|
||||
#define RISING 3
|
||||
|
||||
// Equivalent to HardwareSerial in Arduino
|
||||
class SerialUSBClass
|
||||
{
|
||||
public:
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
#define OCT 8
|
||||
#define BIN 2
|
||||
|
||||
// TODO: move these from being inlined
|
||||
void begin(int baud) {}
|
||||
|
||||
size_t println(const char* s)
|
||||
{
|
||||
print(s);
|
||||
printf("\n");
|
||||
return 0;
|
||||
}
|
||||
size_t print(const char* s)
|
||||
{
|
||||
printf(s);
|
||||
return 0;
|
||||
}
|
||||
size_t print(unsigned int n, int base = DEC)
|
||||
{
|
||||
if (base == DEC)
|
||||
printf("%d", n);
|
||||
else if (base == HEX)
|
||||
printf("%02x", n);
|
||||
else if (base == OCT)
|
||||
printf("%o", n);
|
||||
// TODO: BIN
|
||||
return 0;
|
||||
}
|
||||
size_t print(char ch)
|
||||
{
|
||||
printf("%c", ch);
|
||||
return 0;
|
||||
}
|
||||
size_t println(char ch)
|
||||
{
|
||||
printf("%c\n", ch);
|
||||
return 0;
|
||||
}
|
||||
size_t print(unsigned char ch, int base = DEC)
|
||||
{
|
||||
return print((unsigned int)ch, base);
|
||||
}
|
||||
size_t println(unsigned char ch, int base = DEC)
|
||||
{
|
||||
print((unsigned int)ch, base);
|
||||
printf("\n");
|
||||
return 0;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
// Global instance of the Serial output
|
||||
extern SerialUSBClass SerialUSB;
|
||||
|
||||
#endif
|
||||
|
Reference in New Issue
Block a user