Initial check-in for STM32 board

This commit is contained in:
Ben Lye
2017-11-27 21:19:49 +00:00
parent 9bf5b0c9a7
commit e557155b17
893 changed files with 106516 additions and 34 deletions

View File

@@ -0,0 +1,76 @@
/**
SPI_1 and SPI_2 port example code
Description:
This sketch sends one byte with value 0x55 over the SPI_1 or SPI_2 port.
The received byte (the answer from the SPI slave device) is stored to the <data> variable.
The sketch as it is, works with SPI_1 port. For using the SPI_2 port, just
un-comment all the nessesary code lines marked with <SPI_2> word.
Created on 10 Jun 2015 by Vassilis Serasidis
email: avrsite@yahoo.gr
Using the first SPI port (SPI_1)
SS <--> PA4 <--> BOARD_SPI1_NSS_PIN
SCK <--> PA5 <--> BOARD_SPI1_SCK_PIN
MISO <--> PA6 <--> BOARD_SPI1_MISO_PIN
MOSI <--> PA7 <--> BOARD_SPI1_MOSI_PIN
Using the second SPI port (SPI_2)
SS <--> PB12 <--> BOARD_SPI2_NSS_PIN
SCK <--> PB13 <--> BOARD_SPI2_SCK_PIN
MISO <--> PB14 <--> BOARD_SPI2_MISO_PIN
MOSI <--> PB15 <--> BOARD_SPI2_MOSI_PIN
*/
#include <SPI.h>
#define SPI1_NSS_PIN PA4 //SPI_1 Chip Select pin is PA4. You can change it to the STM32 pin you want.
#define SPI2_NSS_PIN PB12 //SPI_2 Chip Select pin is PB12. You can change it to the STM32 pin you want.
SPIClass SPI_2(2); //Create an instance of the SPI Class called SPI_2 that uses the 2nd SPI Port
byte data;
void setup() {
// Setup SPI 1
SPI.begin(); //Initialize the SPI_1 port.
SPI.setBitOrder(MSBFIRST); // Set the SPI_1 bit order
SPI.setDataMode(SPI_MODE0); //Set the SPI_2 data mode 0
SPI.setClockDivider(SPI_CLOCK_DIV16); // Slow speed (72 / 16 = 4.5 MHz SPI_1 speed)
pinMode(SPI1_NSS_PIN, OUTPUT);
// Setup SPI 2
SPI_2.begin(); //Initialize the SPI_2 port.
SPI_2.setBitOrder(MSBFIRST); // Set the SPI_2 bit order
SPI_2.setDataMode(SPI_MODE0); //Set the SPI_2 data mode 0
SPI_2.setClockDivider(SPI_CLOCK_DIV16); // Use a different speed to SPI 1
pinMode(SPI2_NSS_PIN, OUTPUT);
}
void loop() {
sendSPI();
sendSPI2();
delayMicroseconds(10); //Delay 10 micro seconds.
}
void sendSPI()
{
digitalWrite(SPI1_NSS_PIN, LOW); // manually take CSN low for SPI_1 transmission
data = SPI.transfer(0x55); //Send the HEX data 0x55 over SPI-1 port and store the received byte to the <data> variable.
digitalWrite(SPI1_NSS_PIN, HIGH); // manually take CSN high between spi transmissions
}
void sendSPI2()
{
digitalWrite(SPI2_NSS_PIN, LOW); // manually take CSN low for SPI_2 transmission
data = SPI_2.transfer(0x55); //Send the HEX data 0x55 over SPI-2 port and store the received byte to the <data> variable.
digitalWrite(SPI2_NSS_PIN, HIGH); // manually take CSN high between spi transmissions
}

View File

@@ -0,0 +1,31 @@
#######################################
# Syntax Coloring Map SPI
#######################################
#######################################
# Datatypes (KEYWORD1)
#######################################
SPI KEYWORD1
#######################################
# Methods and Functions (KEYWORD2)
#######################################
begin KEYWORD2
end KEYWORD2
transfer KEYWORD2
#setBitOrder KEYWORD2
setDataMode KEYWORD2
setClockDivider KEYWORD2
#######################################
# Constants (LITERAL1)
#######################################
SPI_MODE0 LITERAL1
SPI_MODE1 LITERAL1
SPI_MODE2 LITERAL1
SPI_MODE3 LITERAL1
SPI_CONTINUE LITERAL1
SPI_LAST LITERAL1

View File

@@ -0,0 +1,10 @@
name=SPI
version=1.0
author=Roger Clark
email=
sentence=Serial Peripheral Interface
paragraph=SPI for STM32F1
url=
architectures=STM32F1
maintainer=
category=Communication

View File

@@ -0,0 +1,776 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @author Marti Bolivar <mbolivar@leaflabs.com>
* @brief Wirish SPI implementation.
*/
#include "SPI.h"
#include <libmaple/timer.h>
#include <libmaple/util.h>
#include <libmaple/rcc.h>
#include "wirish.h"
#include "boards.h"
//#include "HardwareSerial.h"
/** Time in ms for DMA receive timeout */
#define DMA_TIMEOUT 100
#if CYCLES_PER_MICROSECOND != 72
/* TODO [0.2.0?] something smarter than this */
#warning "Unexpected clock speed; SPI frequency calculation will be incorrect"
#endif
struct spi_pins {
uint8 nss;
uint8 sck;
uint8 miso;
uint8 mosi;
};
static const spi_pins* dev_to_spi_pins(spi_dev *dev);
static void configure_gpios(spi_dev *dev, bool as_master);
static spi_baud_rate determine_baud_rate(spi_dev *dev, uint32_t freq);
#if (BOARD_NR_SPI >= 3) && !defined(STM32_HIGH_DENSITY)
#error "The SPI library is misconfigured: 3 SPI ports only available on high density STM32 devices"
#endif
static const spi_pins board_spi_pins[] __FLASH__ = {
#if BOARD_NR_SPI >= 1
{BOARD_SPI1_NSS_PIN,
BOARD_SPI1_SCK_PIN,
BOARD_SPI1_MISO_PIN,
BOARD_SPI1_MOSI_PIN},
#endif
#if BOARD_NR_SPI >= 2
{BOARD_SPI2_NSS_PIN,
BOARD_SPI2_SCK_PIN,
BOARD_SPI2_MISO_PIN,
BOARD_SPI2_MOSI_PIN},
#endif
#if BOARD_NR_SPI >= 3
{BOARD_SPI3_NSS_PIN,
BOARD_SPI3_SCK_PIN,
BOARD_SPI3_MISO_PIN,
BOARD_SPI3_MOSI_PIN},
#endif
};
/*
* Constructor
*/
SPIClass::SPIClass(uint32 spi_num)
{
_currentSetting=&_settings[spi_num-1];// SPI channels are called 1 2 and 3 but the array is zero indexed
switch (spi_num) {
#if BOARD_NR_SPI >= 1
case 1:
_currentSetting->spi_d = SPI1;
_spi1_this = (void*) this;
break;
#endif
#if BOARD_NR_SPI >= 2
case 2:
_currentSetting->spi_d = SPI2;
_spi2_this = (void*) this;
break;
#endif
#if BOARD_NR_SPI >= 3
case 3:
_currentSetting->spi_d = SPI3;
_spi3_this = (void*) this;
break;
#endif
default:
ASSERT(0);
}
// Init things specific to each SPI device
// clock divider setup is a bit of hack, and needs to be improved at a later date.
_settings[0].spi_d = SPI1;
_settings[0].clockDivider = determine_baud_rate(_settings[0].spi_d, _settings[0].clock);
_settings[0].spiDmaDev = DMA1;
_settings[0].spiTxDmaChannel = DMA_CH3;
_settings[0].spiRxDmaChannel = DMA_CH2;
_settings[1].spi_d = SPI2;
_settings[1].clockDivider = determine_baud_rate(_settings[1].spi_d, _settings[1].clock);
_settings[1].spiDmaDev = DMA1;
_settings[1].spiTxDmaChannel = DMA_CH5;
_settings[1].spiRxDmaChannel = DMA_CH4;
#if BOARD_NR_SPI >= 3
_settings[2].spi_d = SPI3;
_settings[2].clockDivider = determine_baud_rate(_settings[2].spi_d, _settings[2].clock);
_settings[2].spiDmaDev = DMA2;
_settings[2].spiTxDmaChannel = DMA_CH2;
_settings[2].spiRxDmaChannel = DMA_CH1;
#endif
// added for DMA callbacks.
_currentSetting->state = SPI_STATE_IDLE;
}
/*
* Set up/tear down
*/
void SPIClass::updateSettings(void) {
uint32 flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize | SPI_SW_SLAVE | SPI_SOFT_SS);
spi_master_enable(_currentSetting->spi_d, (spi_baud_rate)_currentSetting->clockDivider, (spi_mode)_currentSetting->dataMode, flags);
}
void SPIClass::begin(void) {
spi_init(_currentSetting->spi_d);
configure_gpios(_currentSetting->spi_d, 1);
updateSettings();
// added for DMA callbacks.
_currentSetting->state = SPI_STATE_READY;
}
void SPIClass::beginSlave(void) {
spi_init(_currentSetting->spi_d);
configure_gpios(_currentSetting->spi_d, 0);
uint32 flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize | SPI_RX_ONLY);
spi_slave_enable(_currentSetting->spi_d, (spi_mode)_currentSetting->dataMode, flags);
// added for DMA callbacks.
_currentSetting->state = SPI_STATE_READY;
}
void SPIClass::end(void) {
if (!spi_is_enabled(_currentSetting->spi_d)) {
return;
}
// Follows RM0008's sequence for disabling a SPI in master/slave
// full duplex mode.
while (spi_is_rx_nonempty(_currentSetting->spi_d)) {
// FIXME [0.1.0] remove this once you have an interrupt based driver
volatile uint16 rx __attribute__((unused)) = spi_rx_reg(_currentSetting->spi_d);
}
while (!spi_is_tx_empty(_currentSetting->spi_d))
;
while (spi_is_busy(_currentSetting->spi_d))
;
spi_peripheral_disable(_currentSetting->spi_d);
// added for DMA callbacks.
// Need to add unsetting the callbacks for the DMA channels.
_currentSetting->state = SPI_STATE_IDLE;
}
/* Roger Clark added 3 functions */
void SPIClass::setClockDivider(uint32_t clockDivider)
{
_currentSetting->clockDivider = clockDivider;
uint32 cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_BR);
_currentSetting->spi_d->regs->CR1 = cr1 | (clockDivider & SPI_CR1_BR);
}
void SPIClass::setBitOrder(BitOrder bitOrder)
{
_currentSetting->bitOrder = bitOrder;
uint32 cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_LSBFIRST);
if ( bitOrder==LSBFIRST ) cr1 |= SPI_CR1_LSBFIRST;
_currentSetting->spi_d->regs->CR1 = cr1;
}
/* Victor Perez. Added to test changing datasize from 8 to 16 bit modes on the fly.
* Input parameter should be SPI_CR1_DFF set to 0 or 1 on a 32bit word.
*
*/
void SPIClass::setDataSize(uint32 datasize)
{
_currentSetting->dataSize = datasize;
uint32 cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_DFF);
uint8 en = spi_is_enabled(_currentSetting->spi_d);
spi_peripheral_disable(_currentSetting->spi_d);
_currentSetting->spi_d->regs->CR1 = cr1 | (datasize & SPI_CR1_DFF) | en;
}
void SPIClass::setDataMode(uint8_t dataMode)
{
/* Notes. As far as I can tell, the AVR numbers for dataMode appear to match the numbers required by the STM32
From the AVR doc http://www.atmel.com/images/doc2585.pdf section 2.4
SPI Mode CPOL CPHA Shift SCK-edge Capture SCK-edge
0 0 0 Falling Rising
1 0 1 Rising Falling
2 1 0 Rising Falling
3 1 1 Falling Rising
On the STM32 it appears to be
bit 1 - CPOL : Clock polarity
(This bit should not be changed when communication is ongoing)
0 : CLK to 0 when idle
1 : CLK to 1 when idle
bit 0 - CPHA : Clock phase
(This bit should not be changed when communication is ongoing)
0 : The first clock transition is the first data capture edge
1 : The second clock transition is the first data capture edge
If someone finds this is not the case or sees a logic error with this let me know ;-)
*/
_currentSetting->dataMode = dataMode;
uint32 cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_CPOL|SPI_CR1_CPHA);
_currentSetting->spi_d->regs->CR1 = cr1 | (dataMode & (SPI_CR1_CPOL|SPI_CR1_CPHA));
}
void SPIClass::beginTransaction(uint8_t pin, SPISettings settings)
{
setBitOrder(settings.bitOrder);
setDataMode(settings.dataMode);
setDataSize(settings.dataSize);
setClockDivider(determine_baud_rate(_currentSetting->spi_d, settings.clock));
begin();
}
void SPIClass::beginTransactionSlave(SPISettings settings)
{
setBitOrder(settings.bitOrder);
setDataMode(settings.dataMode);
setDataSize(settings.dataSize);
beginSlave();
}
void SPIClass::endTransaction(void)
{
//digitalWrite(_SSPin,HIGH);
#if false
// code from SAM core
uint8_t mode = interruptMode;
if (mode > 0) {
if (mode < 16) {
if (mode & 1) PIOA->PIO_IER = interruptMask[0];
if (mode & 2) PIOB->PIO_IER = interruptMask[1];
if (mode & 4) PIOC->PIO_IER = interruptMask[2];
if (mode & 8) PIOD->PIO_IER = interruptMask[3];
} else {
if (interruptSave) interrupts();
}
}
#endif
}
/*
* I/O
*/
uint16 SPIClass::read(void)
{
while ( spi_is_rx_nonempty(_currentSetting->spi_d)==0 ) ;
return (uint16)spi_rx_reg(_currentSetting->spi_d);
}
void SPIClass::read(uint8 *buf, uint32 len)
{
if ( len == 0 ) return;
spi_rx_reg(_currentSetting->spi_d); // clear the RX buffer in case a byte is waiting on it.
spi_reg_map * regs = _currentSetting->spi_d->regs;
// start sequence: write byte 0
regs->DR = 0x00FF; // write the first byte
// main loop
while ( (--len) ) {
while( !(regs->SR & SPI_SR_TXE) ); // wait for TXE flag
noInterrupts(); // go atomic level - avoid interrupts to surely get the previously received data
regs->DR = 0x00FF; // write the next data item to be transmitted into the SPI_DR register. This clears the TXE flag.
while ( !(regs->SR & SPI_SR_RXNE) ); // wait till data is available in the DR register
*buf++ = (uint8)(regs->DR); // read and store the received byte. This clears the RXNE flag.
interrupts(); // let systick do its job
}
// read remaining last byte
while ( !(regs->SR & SPI_SR_RXNE) ); // wait till data is available in the Rx register
*buf++ = (uint8)(regs->DR); // read and store the received byte
}
void SPIClass::write(uint16 data)
{
/* Added for 16bit data Victor Perez. Roger Clark
* Improved speed by just directly writing the single byte to the SPI data reg and wait for completion,
* by taking the Tx code from transfer(byte)
* This almost doubles the speed of this function.
*/
spi_tx_reg(_currentSetting->spi_d, data); // write the data to be transmitted into the SPI_DR register (this clears the TXE flag)
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
}
void SPIClass::write16(uint16 data)
{
// Added by stevestrong: write two consecutive bytes in 8 bit mode (DFF=0)
spi_tx_reg(_currentSetting->spi_d, data>>8); // write high byte
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // Wait until TXE=1
spi_tx_reg(_currentSetting->spi_d, data); // write low byte
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // Wait until TXE=1
while (spi_is_busy(_currentSetting->spi_d) != 0); // wait until BSY=0
}
void SPIClass::write(uint16 data, uint32 n)
{
// Added by stevstrong: Repeatedly send same data by the specified number of times
spi_reg_map * regs = _currentSetting->spi_d->regs;
while ( (n--)>0 ) {
regs->DR = data; // write the data to be transmitted into the SPI_DR register (this clears the TXE flag)
while ( (regs->SR & SPI_SR_TXE)==0 ) ; // wait till Tx empty
}
while ( (regs->SR & SPI_SR_BSY) != 0); // wait until BSY=0 before returning
}
void SPIClass::write(const void *data, uint32 length)
{
spi_dev * spi_d = _currentSetting->spi_d;
spi_tx(spi_d, data, length); // data can be array of bytes or words
while (spi_is_tx_empty(spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
}
uint8 SPIClass::transfer(uint8 byte) const
{
spi_dev * spi_d = _currentSetting->spi_d;
spi_rx_reg(spi_d); // read any previous data
spi_tx_reg(spi_d, byte); // Write the data item to be transmitted into the SPI_DR register
while (spi_is_tx_empty(spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
return (uint8)spi_rx_reg(spi_d); // "... and read the last received data."
}
uint16_t SPIClass::transfer16(uint16_t data) const
{
// Modified by stevestrong: write & read two consecutive bytes in 8 bit mode (DFF=0)
// This is more effective than two distinct byte transfers
spi_dev * spi_d = _currentSetting->spi_d;
spi_rx_reg(spi_d); // read any previous data
spi_tx_reg(spi_d, data>>8); // write high byte
while (spi_is_tx_empty(spi_d) == 0); // wait until TXE=1
while (spi_is_busy(spi_d) != 0); // wait until BSY=0
uint16_t ret = spi_rx_reg(spi_d)<<8; // read and shift high byte
spi_tx_reg(spi_d, data); // write low byte
while (spi_is_tx_empty(spi_d) == 0); // wait until TXE=1
while (spi_is_busy(spi_d) != 0); // wait until BSY=0
ret += spi_rx_reg(spi_d); // read low byte
return ret;
}
/* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI transfer with at least a receive buffer.
* If a TX buffer is not provided, FF is sent over and over for the lenght of the transfer.
* On exit TX buffer is not modified, and RX buffer cotains the received data.
* Still in progress.
*/
void SPIClass::dmaTransferSet(const void *transmitBuf, void *receiveBuf) {
dma_init(_currentSetting->spiDmaDev);
//spi_rx_dma_enable(_currentSetting->spi_d);
//spi_tx_dma_enable(_currentSetting->spi_d);
dma_xfer_size dma_bit_size = (_currentSetting->dataSize==DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size,
receiveBuf, dma_bit_size, (DMA_MINC_MODE | DMA_TRNS_CMPLT ));// receive buffer DMA
if (!transmitBuf) {
transmitBuf = &ff;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size,
(volatile void*)transmitBuf, dma_bit_size, (DMA_FROM_MEM));// Transmit FF repeatedly
}
else {
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size,
(volatile void*)transmitBuf, dma_bit_size, (DMA_MINC_MODE | DMA_FROM_MEM ));// Transmit buffer DMA
}
dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, DMA_PRIORITY_LOW);
dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, DMA_PRIORITY_VERY_HIGH);
}
uint8 SPIClass::dmaTransferRepeat(uint16 length) {
if (length == 0) return 0;
if (spi_is_rx_nonempty(_currentSetting->spi_d) == 1) spi_rx_reg(_currentSetting->spi_d);
_currentSetting->state = SPI_STATE_TRANSFER;
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, length);
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);// enable receive
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);// enable transmit
spi_rx_dma_enable(_currentSetting->spi_d);
spi_tx_dma_enable(_currentSetting->spi_d);
if (_currentSetting->receiveCallback){
return 0;
}
//uint32_t m = millis();
uint8 b = 0;
uint32_t m = millis();
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)==0) {
//Avoid interrupts and just loop waiting for the flag to be set.
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
}
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
spi_tx_dma_disable(_currentSetting->spi_d);
spi_rx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
_currentSetting->state = SPI_STATE_READY;
return b;
}
/* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI transfer with at least a receive buffer.
* If a TX buffer is not provided, FF is sent over and over for the length of the transfer.
* On exit TX buffer is not modified, and RX buffer contains the received data.
* Still in progress.
*/
uint8 SPIClass::dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16 length) {
dmaTransferSet(transmitBuf, receiveBuf);
return dmaTransferRepeat(length);
}
/* Roger Clark and Victor Perez, 2015
* Performs a DMA SPI send using a TX buffer.
* On exit TX buffer is not modified.
* Still in progress.
* 2016 - stevstrong - reworked to automatically detect bit size from SPI setting
*/
void SPIClass::dmaSendSet(const void * transmitBuf, bool minc) {
uint32 flags = ( (DMA_MINC_MODE*minc) | DMA_FROM_MEM | DMA_TRNS_CMPLT);
dma_init(_currentSetting->spiDmaDev);
dma_xfer_size dma_bit_size = (_currentSetting->dataSize==DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size,
(volatile void*)transmitBuf, dma_bit_size, flags);// Transmit buffer DMA
dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, DMA_PRIORITY_LOW);
}
uint8 SPIClass::dmaSendRepeat(uint16 length) {
if (length == 0) return 0;
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
_currentSetting->state = SPI_STATE_TRANSMIT;
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);// enable transmit
spi_tx_dma_enable(_currentSetting->spi_d);
if (_currentSetting->transmitCallback)
{
return 0;
}
uint32_t m = millis();
uint8 b = 0;
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)==0) {
//Avoid interrupts and just loop waiting for the flag to be set.
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
}
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
spi_tx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
_currentSetting->state = SPI_STATE_READY;
return b;
}
uint8 SPIClass::dmaSend(const void * transmitBuf, uint16 length, bool minc) {
dmaSendSet(transmitBuf, minc);
return dmaSendRepeat(length);
}
uint8 SPIClass::dmaSendAsync(const void * transmitBuf, uint16 length, bool minc) {
uint8 b = 0;
if (_currentSetting->state != SPI_STATE_READY)
{
uint32_t m = millis();
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)==0) {//Avoid interrupts and just loop waiting for the flag to be set.
//delayMicroseconds(10);
if ((millis() - m) > DMA_TIMEOUT) { b = 2; break; }
}
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0 before disabling the SPI."
spi_tx_dma_disable(_currentSetting->spi_d);
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
_currentSetting->state = SPI_STATE_READY;
}
if (length == 0) return 0;
uint32 flags = ( (DMA_MINC_MODE*minc) | DMA_FROM_MEM | DMA_TRNS_CMPLT);
dma_init(_currentSetting->spiDmaDev);
// TX
dma_xfer_size dma_bit_size = (_currentSetting->dataSize==DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS;
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size,
(volatile void*)transmitBuf, dma_bit_size, flags);// Transmit buffer DMA
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);// enable transmit
spi_tx_dma_enable(_currentSetting->spi_d);
_currentSetting->state = SPI_STATE_TRANSMIT;
return b;
}
/*
New functions added to manage callbacks.
Victor Perez 2017
*/
void SPIClass::onReceive(void(*callback)(void)) {
_currentSetting->receiveCallback = callback;
if (callback){
switch (_currentSetting->spi_d->clk_id) {
case RCC_SPI1:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi1EventCallback);
break;
case RCC_SPI2:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi2EventCallback);
break;
#if BOARD_NR_SPI >= 3
case RCC_SPI3:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi3EventCallback);
break;
#endif
default:
ASSERT(0);
}
}
else {
dma_detach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
}
}
void SPIClass::onTransmit(void(*callback)(void)) {
_currentSetting->transmitCallback = callback;
if (callback){
switch (_currentSetting->spi_d->clk_id) {
case RCC_SPI1:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi1EventCallback);
break;
case RCC_SPI2:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi2EventCallback);
break;
#if BOARD_NR_SPI >= 3
case RCC_SPI3:
dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi3EventCallback);
break;
#endif
default:
ASSERT(0);
}
}
else {
dma_detach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
}
}
/*
TODO: check if better to first call the customer code, next disable the DMA requests.
Also see if we need to check whether callbacks are set or not, may be better to be checked during the initial setup and only set the callback to EventCallback if they are set.
*/
void SPIClass::EventCallback() {
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "5. Wait until TXE=1 ..."
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... and then wait until BSY=0"
switch (_currentSetting->state) {
case SPI_STATE_TRANSFER:
while (spi_is_rx_nonempty(_currentSetting->spi_d));
_currentSetting->state = SPI_STATE_READY;
spi_tx_dma_disable(_currentSetting->spi_d);
spi_rx_dma_disable(_currentSetting->spi_d);
//dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
//dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
if (_currentSetting->receiveCallback)
{
_currentSetting->receiveCallback();
}
break;
case SPI_STATE_TRANSMIT:
_currentSetting->state = SPI_STATE_READY;
spi_tx_dma_disable(_currentSetting->spi_d);
//dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
if (_currentSetting->transmitCallback)
{
_currentSetting->transmitCallback();
}
break;
default:
// we shouldn't get here, so better to add an assert and fail.
return;
}
}
void SPIClass::attachInterrupt(void) {
// Should be enableInterrupt()
}
void SPIClass::detachInterrupt(void) {
// Should be disableInterrupt()
}
/*
* Pin accessors
*/
uint8 SPIClass::misoPin(void) {
return dev_to_spi_pins(_currentSetting->spi_d)->miso;
}
uint8 SPIClass::mosiPin(void) {
return dev_to_spi_pins(_currentSetting->spi_d)->mosi;
}
uint8 SPIClass::sckPin(void) {
return dev_to_spi_pins(_currentSetting->spi_d)->sck;
}
uint8 SPIClass::nssPin(void) {
return dev_to_spi_pins(_currentSetting->spi_d)->nss;
}
/*
* Deprecated functions
*/
uint8 SPIClass::send(uint8 data) {
this->write(data);
return 1;
}
uint8 SPIClass::send(uint8 *buf, uint32 len) {
this->write(buf, len);
return len;
}
uint8 SPIClass::recv(void) {
return this->read();
}
/*
DMA call back functions, one per port.
*/
void SPIClass::_spi1EventCallback()
{
reinterpret_cast<class SPIClass*>(_spi1_this)->EventCallback();
}
void SPIClass::_spi2EventCallback() {
reinterpret_cast<class SPIClass*>(_spi2_this)->EventCallback();
}
#if BOARD_NR_SPI >= 3
void SPIClass::_spi3EventCallback() {
reinterpret_cast<class SPIClass*>(_spi3_this)->EventCallback();
}
#endif
/*
* Auxiliary functions
*/
static const spi_pins* dev_to_spi_pins(spi_dev *dev) {
switch (dev->clk_id) {
#if BOARD_NR_SPI >= 1
case RCC_SPI1: return board_spi_pins;
#endif
#if BOARD_NR_SPI >= 2
case RCC_SPI2: return board_spi_pins + 1;
#endif
#if BOARD_NR_SPI >= 3
case RCC_SPI3: return board_spi_pins + 2;
#endif
default: return NULL;
}
}
static void disable_pwm(const stm32_pin_info *i) {
if (i->timer_device) {
timer_set_mode(i->timer_device, i->timer_channel, TIMER_DISABLED);
}
}
static void configure_gpios(spi_dev *dev, bool as_master) {
const spi_pins *pins = dev_to_spi_pins(dev);
if (!pins) {
return;
}
const stm32_pin_info *nssi = &PIN_MAP[pins->nss];
const stm32_pin_info *scki = &PIN_MAP[pins->sck];
const stm32_pin_info *misoi = &PIN_MAP[pins->miso];
const stm32_pin_info *mosii = &PIN_MAP[pins->mosi];
disable_pwm(nssi);
disable_pwm(scki);
disable_pwm(misoi);
disable_pwm(mosii);
spi_config_gpios(dev, as_master, nssi->gpio_device, nssi->gpio_bit,
scki->gpio_device, scki->gpio_bit, misoi->gpio_bit,
mosii->gpio_bit);
}
static const spi_baud_rate baud_rates[8] __FLASH__ = {
SPI_BAUD_PCLK_DIV_2,
SPI_BAUD_PCLK_DIV_4,
SPI_BAUD_PCLK_DIV_8,
SPI_BAUD_PCLK_DIV_16,
SPI_BAUD_PCLK_DIV_32,
SPI_BAUD_PCLK_DIV_64,
SPI_BAUD_PCLK_DIV_128,
SPI_BAUD_PCLK_DIV_256,
};
/*
* Note: This assumes you're on a LeafLabs-style board
* (CYCLES_PER_MICROSECOND == 72, APB2 at 72MHz, APB1 at 36MHz).
*/
static spi_baud_rate determine_baud_rate(spi_dev *dev, uint32_t freq) {
uint32_t clock = 0, i;
switch (rcc_dev_clk(dev->clk_id))
{
case RCC_APB2: clock = STM32_PCLK2; break; // 72 Mhz
case RCC_APB1: clock = STM32_PCLK1; break; // 36 Mhz
}
clock /= 2;
i = 0;
while (i < 7 && freq < clock) {
clock /= 2;
i++;
}
return baud_rates[i];
}
SPIClass SPI(1);

View File

@@ -0,0 +1,430 @@
/******************************************************************************
* The MIT License
*
* Copyright (c) 2010 Perry Hung.
*
* Permission is hereby granted, free of charge, to any person
* obtaining a copy of this software and associated documentation
* files (the "Software"), to deal in the Software without
* restriction, including without limitation the rights to use, copy,
* modify, merge, publish, distribute, sublicense, and/or sell copies
* of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
* BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
* ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*****************************************************************************/
/**
* @file wirish/include/wirish/HardwareSPI.h
* @brief High-level SPI interface
*
* This is a "bare essentials" polling driver for now.
*/
/* TODO [0.1.0] Remove deprecated methods. */
#ifndef _SPI_H_INCLUDED
#define _SPI_H_INCLUDED
#include <libmaple/libmaple_types.h>
#include <libmaple/spi.h>
#include <libmaple/dma.h>
#include <boards.h>
#include <stdint.h>
#include <wirish.h>
// SPI_HAS_TRANSACTION means SPI has
// - beginTransaction()
// - endTransaction()
// - usingInterrupt()
// - SPISetting(clock, bitOrder, dataMode)
//#define SPI_HAS_TRANSACTION
#define SPI_CLOCK_DIV2 SPI_BAUD_PCLK_DIV_2
#define SPI_CLOCK_DIV4 SPI_BAUD_PCLK_DIV_4
#define SPI_CLOCK_DIV8 SPI_BAUD_PCLK_DIV_8
#define SPI_CLOCK_DIV16 SPI_BAUD_PCLK_DIV_16
#define SPI_CLOCK_DIV32 SPI_BAUD_PCLK_DIV_32
#define SPI_CLOCK_DIV64 SPI_BAUD_PCLK_DIV_64
#define SPI_CLOCK_DIV128 SPI_BAUD_PCLK_DIV_128
#define SPI_CLOCK_DIV256 SPI_BAUD_PCLK_DIV_256
/*
* Roger Clark. 20150106
* Commented out redundant AVR defined
*
#define SPI_MODE_MASK 0x0C // CPOL = bit 3, CPHA = bit 2 on SPCR
#define SPI_CLOCK_MASK 0x03 // SPR1 = bit 1, SPR0 = bit 0 on SPCR
#define SPI_2XCLOCK_MASK 0x01 // SPI2X = bit 0 on SPSR
// define SPI_AVR_EIMSK for AVR boards with external interrupt pins
#if defined(EIMSK)
#define SPI_AVR_EIMSK EIMSK
#elif defined(GICR)
#define SPI_AVR_EIMSK GICR
#elif defined(GIMSK)
#define SPI_AVR_EIMSK GIMSK
#endif
*/
#ifndef STM32_LSBFIRST
#define STM32_LSBFIRST 0
#endif
#ifndef STM32_MSBFIRST
#define STM32_MSBFIRST 1
#endif
// PC13 or PA4
#define BOARD_SPI_DEFAULT_SS PA4
//#define BOARD_SPI_DEFAULT_SS PC13
#define SPI_MODE0 SPI_MODE_0
#define SPI_MODE1 SPI_MODE_1
#define SPI_MODE2 SPI_MODE_2
#define SPI_MODE3 SPI_MODE_3
#define DATA_SIZE_8BIT SPI_CR1_DFF_8_BIT
#define DATA_SIZE_16BIT SPI_CR1_DFF_16_BIT
typedef enum {
SPI_STATE_IDLE,
SPI_STATE_READY,
SPI_STATE_RECEIVE,
SPI_STATE_TRANSMIT,
SPI_STATE_TRANSFER
} spi_mode_t;
class SPISettings {
public:
SPISettings(uint32_t clock, BitOrder bitOrder, uint8_t dataMode) {
if (__builtin_constant_p(clock)) {
init_AlwaysInline(clock, bitOrder, dataMode, DATA_SIZE_8BIT);
} else {
init_MightInline(clock, bitOrder, dataMode, DATA_SIZE_8BIT);
}
}
SPISettings(uint32_t clock, BitOrder bitOrder, uint8_t dataMode, uint32_t dataSize) {
if (__builtin_constant_p(clock)) {
init_AlwaysInline(clock, bitOrder, dataMode, dataSize);
} else {
init_MightInline(clock, bitOrder, dataMode, dataSize);
}
}
SPISettings(uint32_t clock) {
if (__builtin_constant_p(clock)) {
init_AlwaysInline(clock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
} else {
init_MightInline(clock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT);
}
}
SPISettings() { init_AlwaysInline(4000000, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT); }
private:
void init_MightInline(uint32_t clock, BitOrder bitOrder, uint8_t dataMode, uint32_t dataSize) {
init_AlwaysInline(clock, bitOrder, dataMode, dataSize);
}
void init_AlwaysInline(uint32_t clock, BitOrder bitOrder, uint8_t dataMode, uint32_t dataSize) __attribute__((__always_inline__)) {
this->clock = clock;
this->bitOrder = bitOrder;
this->dataMode = dataMode;
this->dataSize = dataSize;
}
uint32_t clock;
uint32_t dataSize;
uint32_t clockDivider;
BitOrder bitOrder;
uint8_t dataMode;
uint8_t _SSPin;
volatile spi_mode_t state;
spi_dev *spi_d;
dma_channel spiRxDmaChannel, spiTxDmaChannel;
dma_dev* spiDmaDev;
void (*receiveCallback)(void) = NULL;
void (*transmitCallback)(void) = NULL;
friend class SPIClass;
};
/*
Should move this to within the class once tested out, just for tidyness
*/
static uint8_t ff = 0XFF;
static void (*_spi1_this);
static void (*_spi2_this);
#if BOARD_NR_SPI >= 3
static void (*_spi3_this);
#endif
/**
* @brief Wirish SPI interface.
*
* This implementation uses software slave management, so the caller
* is responsible for controlling the slave select line.
*/
class SPIClass {
public:
/**
* @param spiPortNumber Number of the SPI port to manage.
*/
SPIClass(uint32 spiPortNumber);
/*
* Set up/tear down
*/
/**
* @brief Equivalent to begin(SPI_1_125MHZ, MSBFIRST, 0).
*/
void begin(void);
/**
* @brief Turn on a SPI port and set its GPIO pin modes for use as a slave.
*
* SPI port is enabled in full duplex mode, with software slave management.
*
* @param bitOrder Either LSBFIRST (little-endian) or MSBFIRST(big-endian)
* @param mode SPI mode to use
*/
void beginSlave(uint32 bitOrder, uint32 mode);
/**
* @brief Equivalent to beginSlave(MSBFIRST, 0).
*/
void beginSlave(void);
/**
* @brief Disables the SPI port, but leaves its GPIO pin modes unchanged.
*/
void end(void);
void beginTransaction(SPISettings settings) { beginTransaction(BOARD_SPI_DEFAULT_SS, settings); }
void beginTransaction(uint8_t pin, SPISettings settings);
void endTransaction(void);
void beginTransactionSlave(SPISettings settings);
void setClockDivider(uint32_t clockDivider);
void setBitOrder(BitOrder bitOrder);
void setDataMode(uint8_t dataMode);
// SPI Configuration methods
void attachInterrupt(void);
void detachInterrupt(void);
/* Victor Perez. Added to change datasize from 8 to 16 bit modes on the fly.
* Input parameter should be SPI_CR1_DFF set to 0 or 1 on a 32bit word.
* Requires an added function spi_data_size on STM32F1 / cores / maple / libmaple / spi.c
*/
void setDataSize(uint32 ds);
/* Victor Perez 2017. Added to set and clear callback functions for callback
* on DMA transfer completion.
* onReceive used to set the callback in case of dmaTransfer (tx/rx), once rx is completed
* onTransmit used to set the callback in case of dmaSend (tx only). That function
* will NOT be called in case of TX/RX
*/
void onReceive(void(*)(void));
void onTransmit(void(*)(void));
/*
* I/O
*/
/**
* @brief Return the next unread byte/word.
*
* If there is no unread byte/word waiting, this function will block
* until one is received.
*/
uint16 read(void);
/**
* @brief Read length bytes, storing them into buffer.
* @param buffer Buffer to store received bytes into.
* @param length Number of bytes to store in buffer. This
* function will block until the desired number of
* bytes have been read.
*/
void read(uint8 *buffer, uint32 length);
/**
* @brief Transmit one byte/word.
* @param data to transmit.
*/
void write(uint16 data);
void write16(uint16 data); // write 2 bytes in 8 bit mode (DFF=0)
/**
* @brief Transmit one byte/word a specified number of times.
* @param data to transmit.
*/
void write(uint16 data, uint32 n);
/**
* @brief Transmit multiple bytes/words.
* @param buffer Bytes/words to transmit.
* @param length Number of bytes/words in buffer to transmit.
*/
void write(const void * buffer, uint32 length);
/**
* @brief Transmit a byte, then return the next unread byte.
*
* This function transmits before receiving.
*
* @param data Byte to transmit.
* @return Next unread byte.
*/
uint8 transfer(uint8 data) const;
uint16_t transfer16(uint16_t data) const;
/**
* @brief Sets up a DMA Transfer for "length" bytes.
* The transfer mode (8 or 16 bit mode) is evaluated from the SPI peripheral setting.
*
* This function transmits and receives to buffers.
*
* @param transmitBuf buffer Bytes to transmit. If passed as 0, it sends FF repeatedly for "length" bytes
* @param receiveBuf buffer Bytes to save received data.
* @param length Number of bytes in buffer to transmit.
*/
uint8 dmaTransfer(const void * transmitBuf, void * receiveBuf, uint16 length);
void dmaTransferSet(const void *transmitBuf, void *receiveBuf);
uint8 dmaTransferRepeat(uint16 length);
/**
* @brief Sets up a DMA Transmit for SPI 8 or 16 bit transfer mode.
* The transfer mode (8 or 16 bit mode) is evaluated from the SPI peripheral setting.
*
* This function only transmits and does not care about the RX fifo.
*
* @param data buffer half words to transmit,
* @param length Number of bytes in buffer to transmit.
* @param minc Set to use Memory Increment mode, clear to use Circular mode.
*/
uint8 dmaSend(const void * transmitBuf, uint16 length, bool minc = 1);
void dmaSendSet(const void * transmitBuf, bool minc);
uint8 dmaSendRepeat(uint16 length);
uint8 dmaSendAsync(const void * transmitBuf, uint16 length, bool minc = 1);
/*
* Pin accessors
*/
/**
* @brief Return the number of the MISO (master in, slave out) pin
*/
uint8 misoPin(void);
/**
* @brief Return the number of the MOSI (master out, slave in) pin
*/
uint8 mosiPin(void);
/**
* @brief Return the number of the SCK (serial clock) pin
*/
uint8 sckPin(void);
/**
* @brief Return the number of the NSS (slave select) pin
*/
uint8 nssPin(void);
/* Escape hatch */
/**
* @brief Get a pointer to the underlying libmaple spi_dev for
* this HardwareSPI instance.
*/
spi_dev* c_dev(void) { return _currentSetting->spi_d; }
spi_dev *dev(){ return _currentSetting->spi_d;}
/**
* @brief Sets the number of the SPI peripheral to be used by
* this HardwareSPI instance.
*
* @param spi_num Number of the SPI port. 1-2 in low density devices
* or 1-3 in high density devices.
*/
void setModule(int spi_num)
{
_currentSetting=&_settings[spi_num-1];// SPI channels are called 1 2 and 3 but the array is zero indexed
}
/* -- The following methods are deprecated --------------------------- */
/**
* @brief Deprecated.
*
* Use HardwareSPI::transfer() instead.
*
* @see HardwareSPI::transfer()
*/
uint8 send(uint8 data);
/**
* @brief Deprecated.
*
* Use HardwareSPI::write() in combination with
* HardwareSPI::read() (or HardwareSPI::transfer()) instead.
*
* @see HardwareSPI::write()
* @see HardwareSPI::read()
* @see HardwareSPI::transfer()
*/
uint8 send(uint8 *data, uint32 length);
/**
* @brief Deprecated.
*
* Use HardwareSPI::read() instead.
*
* @see HardwareSPI::read()
*/
uint8 recv(void);
private:
SPISettings _settings[BOARD_NR_SPI];
SPISettings *_currentSetting;
void updateSettings(void);
/*
* Functions added for DMA transfers with Callback.
* Experimental.
*/
void EventCallback(void);
static void _spi1EventCallback(void);
static void _spi2EventCallback(void);
#if BOARD_NR_SPI >= 3
static void _spi3EventCallback(void);
#endif
/*
spi_dev *spi_d;
uint8_t _SSPin;
uint32_t clockDivider;
uint8_t dataMode;
BitOrder bitOrder;
*/
};
extern SPIClass SPI;//(1);// dummy params
#endif