mirror of
https://github.com/pascallanger/DIY-Multiprotocol-TX-Module.git
synced 2025-02-04 18:38:13 +00:00
Roll back to older STM32 core files (#128)
This commit is contained in:
parent
dc9f738f30
commit
68dcc75949
@ -193,8 +193,7 @@ size_t HardwareSerial::write(unsigned char ch) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* edogaldo: Waits for the transmission of outgoing serial data to complete (Arduino 1.0 api specs) */
|
||||
void HardwareSerial::flush(void) {
|
||||
while(!rb_is_empty(this->usart_device->wb)); // wait for TX buffer empty
|
||||
while(!((this->usart_device->regs->SR) & (1<<USART_SR_TC_BIT))); // wait for TC (Transmission Complete) flag set
|
||||
usart_reset_rx(this->usart_device);
|
||||
usart_reset_tx(this->usart_device);
|
||||
}
|
||||
|
@ -138,24 +138,10 @@ void HardwareTimer::detachInterrupt(int channel) {
|
||||
timer_detach_interrupt(this->dev, (uint8)channel);
|
||||
}
|
||||
|
||||
|
||||
void HardwareTimer::enableDMA(int channel) {
|
||||
timer_dma_enable_req(this->dev, (uint8)channel);
|
||||
}
|
||||
|
||||
void HardwareTimer::disableDMA(int channel) {
|
||||
timer_dma_disable_req(this->dev, (uint8)channel);
|
||||
}
|
||||
|
||||
void HardwareTimer::refresh(void) {
|
||||
timer_generate_update(this->dev);
|
||||
}
|
||||
|
||||
void HardwareTimer::setMasterModeTrGo(uint32_t mode) {
|
||||
this->dev->regs.bas->CR2 &= ~TIMER_CR2_MMS;
|
||||
this->dev->regs.bas->CR2 |= mode;
|
||||
}
|
||||
|
||||
/* CARLOS Changes to add encoder mode.*/
|
||||
|
||||
//direction of movement. (to be better described).
|
||||
|
@ -209,23 +209,6 @@ public:
|
||||
*/
|
||||
void refresh(void);
|
||||
|
||||
// SYFRE
|
||||
/**
|
||||
* @brief Set the Master mode TRGO signal
|
||||
* These bits allow to select the information to be sent in master mode to slave timers for
|
||||
* synchronization (TRGO).
|
||||
* mode:
|
||||
* TIMER_CR2_MMS_RESET
|
||||
* TIMER_CR2_MMS_ENABLE
|
||||
* TIMER_CR2_MMS_UPDATE
|
||||
* TIMER_CR2_MMS_COMPARE_PULSE
|
||||
* TIMER_CR2_MMS_COMPARE_OC1REF
|
||||
* TIMER_CR2_MMS_COMPARE_OC2REF
|
||||
* TIMER_CR2_MMS_COMPARE_OC3REF
|
||||
* TIMER_CR2_MMS_COMPARE_OC4REF
|
||||
*/
|
||||
void setMasterModeTrGo(uint32_t mode);
|
||||
|
||||
//CARLOS.
|
||||
/*
|
||||
added these functions to make sense for the encoder mode.
|
||||
@ -245,12 +228,6 @@ public:
|
||||
|
||||
/* Escape hatch */
|
||||
|
||||
/**
|
||||
* @brief Enable/disable DMA request for the input channel.
|
||||
*/
|
||||
void enableDMA(int channel);
|
||||
void disableDMA(int channel);
|
||||
|
||||
/**
|
||||
* @brief Get a pointer to the underlying libmaple timer_dev for
|
||||
* this HardwareTimer instance.
|
||||
|
@ -44,48 +44,6 @@ IPAddress::IPAddress(const uint8_t *address)
|
||||
memcpy(_address.bytes, address, sizeof(_address.bytes));
|
||||
}
|
||||
|
||||
bool IPAddress::fromString(const char *address)
|
||||
{
|
||||
// TODO: add support for "a", "a.b", "a.b.c" formats
|
||||
|
||||
uint16_t acc = 0; // Accumulator
|
||||
uint8_t dots = 0;
|
||||
|
||||
while (*address)
|
||||
{
|
||||
char c = *address++;
|
||||
if (c >= '0' && c <= '9')
|
||||
{
|
||||
acc = acc * 10 + (c - '0');
|
||||
if (acc > 255) {
|
||||
// Value out of [0..255] range
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else if (c == '.')
|
||||
{
|
||||
if (dots == 3) {
|
||||
// Too much dots (there must be 3 dots)
|
||||
return false;
|
||||
}
|
||||
_address.bytes[dots++] = acc;
|
||||
acc = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Invalid char
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
if (dots != 3) {
|
||||
// Too few dots (there must be 3 dots)
|
||||
return false;
|
||||
}
|
||||
_address.bytes[3] = acc;
|
||||
return true;
|
||||
}
|
||||
|
||||
IPAddress& IPAddress::operator=(const uint8_t *address)
|
||||
{
|
||||
memcpy(_address.bytes, address, sizeof(_address.bytes));
|
||||
|
@ -46,9 +46,6 @@ public:
|
||||
IPAddress(uint32_t address);
|
||||
IPAddress(const uint8_t *address);
|
||||
|
||||
bool fromString(const char *address);
|
||||
bool fromString(const String &address) { return fromString(address.c_str()); }
|
||||
|
||||
// Overloaded cast operator to allow IPAddress objects to be used where a pointer
|
||||
// to a four-byte uint8_t array is expected
|
||||
operator uint32_t() const { return _address.dword; };
|
||||
|
@ -99,6 +99,10 @@ size_t Print::print(unsigned long n, int base) {
|
||||
}
|
||||
|
||||
size_t Print::print(long long n, int base) {
|
||||
if (base == BYTE)
|
||||
{
|
||||
return write((uint8)n);
|
||||
}
|
||||
if (n < 0) {
|
||||
print('-');
|
||||
n = -n;
|
||||
@ -107,23 +111,19 @@ size_t Print::print(long long n, int base) {
|
||||
}
|
||||
|
||||
size_t Print::print(unsigned long long n, int base) {
|
||||
return printNumber(n, base);
|
||||
size_t c=0;
|
||||
if (base == BYTE) {
|
||||
c= write((uint8)n);
|
||||
} else {
|
||||
c= printNumber(n, base);
|
||||
}
|
||||
return c;
|
||||
}
|
||||
|
||||
size_t Print::print(double n, int digits) {
|
||||
return printFloat(n, digits);
|
||||
}
|
||||
|
||||
size_t Print::print(const __FlashStringHelper *ifsh)
|
||||
{
|
||||
return print(reinterpret_cast<const char *>(ifsh));
|
||||
}
|
||||
|
||||
size_t Print::print(const Printable& x)
|
||||
{
|
||||
return x.printTo(*this);
|
||||
}
|
||||
|
||||
size_t Print::println(void)
|
||||
{
|
||||
size_t n = print('\r');
|
||||
@ -198,20 +198,6 @@ size_t Print::println(double n, int digits) {
|
||||
return s;
|
||||
}
|
||||
|
||||
size_t Print::println(const __FlashStringHelper *ifsh)
|
||||
{
|
||||
size_t n = print(ifsh);
|
||||
n += println();
|
||||
return n;
|
||||
}
|
||||
|
||||
size_t Print::println(const Printable& x)
|
||||
{
|
||||
size_t n = print(x);
|
||||
n += println();
|
||||
return n;
|
||||
}
|
||||
|
||||
#ifdef SUPPORTS_PRINTF
|
||||
#include <stdio.h>
|
||||
#include <stdarg.h>
|
||||
|
@ -25,9 +25,9 @@
|
||||
|
||||
#include <libmaple/libmaple_types.h>
|
||||
#include "WString.h"
|
||||
#include "Printable.h"
|
||||
|
||||
enum {
|
||||
BYTE = 0,
|
||||
BIN = 2,
|
||||
OCT = 8,
|
||||
DEC = 10,
|
||||
@ -51,8 +51,6 @@ public:
|
||||
size_t print(long long, int=DEC);
|
||||
size_t print(unsigned long long, int=DEC);
|
||||
size_t print(double, int=2);
|
||||
size_t print(const __FlashStringHelper *);
|
||||
size_t print(const Printable&);
|
||||
size_t println(void);
|
||||
size_t println(const String &s);
|
||||
size_t println(char);
|
||||
@ -65,8 +63,6 @@ public:
|
||||
size_t println(long long, int=DEC);
|
||||
size_t println(unsigned long long, int=DEC);
|
||||
size_t println(double, int=2);
|
||||
size_t println(const __FlashStringHelper *);
|
||||
size_t println(const Printable&);
|
||||
#ifdef SUPPORTS_PRINTF
|
||||
// Roger Clark. Work in progress to add printf support
|
||||
int printf(const char * format, ...);
|
||||
|
@ -268,68 +268,3 @@ String Stream::readStringUntil(char terminator)
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
int Stream::findMulti( struct Stream::MultiTarget *targets, int tCount) {
|
||||
// any zero length target string automatically matches and would make
|
||||
// a mess of the rest of the algorithm.
|
||||
for (struct MultiTarget *t = targets; t < targets+tCount; ++t) {
|
||||
if (t->len <= 0)
|
||||
return t - targets;
|
||||
}
|
||||
|
||||
while (1) {
|
||||
int c = timedRead();
|
||||
if (c < 0)
|
||||
return -1;
|
||||
|
||||
for (struct MultiTarget *t = targets; t < targets+tCount; ++t) {
|
||||
// the simple case is if we match, deal with that first.
|
||||
if (c == t->str[t->index]) {
|
||||
if (++t->index == t->len)
|
||||
return t - targets;
|
||||
else
|
||||
continue;
|
||||
}
|
||||
|
||||
// if not we need to walk back and see if we could have matched further
|
||||
// down the stream (ie '1112' doesn't match the first position in '11112'
|
||||
// but it will match the second position so we can't just reset the current
|
||||
// index to 0 when we find a mismatch.
|
||||
if (t->index == 0)
|
||||
continue;
|
||||
|
||||
int origIndex = t->index;
|
||||
do {
|
||||
--t->index;
|
||||
// first check if current char works against the new current index
|
||||
if (c != t->str[t->index])
|
||||
continue;
|
||||
|
||||
// if it's the only char then we're good, nothing more to check
|
||||
if (t->index == 0) {
|
||||
t->index++;
|
||||
break;
|
||||
}
|
||||
|
||||
// otherwise we need to check the rest of the found string
|
||||
int diff = origIndex - t->index;
|
||||
size_t i;
|
||||
for (i = 0; i < t->index; ++i) {
|
||||
if (t->str[i] != t->str[i + diff])
|
||||
break;
|
||||
}
|
||||
|
||||
// if we successfully got through the previous loop then our current
|
||||
// index is good.
|
||||
if (i == t->index) {
|
||||
t->index++;
|
||||
break;
|
||||
}
|
||||
|
||||
// otherwise we just try the next index
|
||||
} while (t->index);
|
||||
}
|
||||
}
|
||||
// unreachable
|
||||
return -1;
|
||||
}
|
||||
|
@ -55,7 +55,6 @@ class Stream : public Print
|
||||
// parsing methods
|
||||
|
||||
void setTimeout(unsigned long timeout); // sets maximum milliseconds to wait for stream data, default is 1 second
|
||||
unsigned long getTimeout(void) { return _timeout; }
|
||||
|
||||
bool find(char *target); // reads data from the stream until the target string is found
|
||||
bool find(uint8_t *target) { return find ((char *)target); }
|
||||
@ -65,8 +64,6 @@ class Stream : public Print
|
||||
bool find(uint8_t *target, size_t length) { return find ((char *)target, length); }
|
||||
// returns true if target string is found, false if timed out
|
||||
|
||||
bool find(char target) { return find (&target, 1); }
|
||||
|
||||
bool findUntil(char *target, char *terminator); // as find but search ends if the terminator string is found
|
||||
bool findUntil(uint8_t *target, char *terminator) { return findUntil((char *)target, terminator); }
|
||||
|
||||
@ -100,16 +97,6 @@ class Stream : public Print
|
||||
// this allows format characters (typically commas) in values to be ignored
|
||||
|
||||
float parseFloat(char skipChar); // as above but the given skipChar is ignored
|
||||
|
||||
struct MultiTarget {
|
||||
const char *str; // string you're searching for
|
||||
size_t len; // length of string you're searching for
|
||||
size_t index; // index used by the search routine.
|
||||
};
|
||||
|
||||
// This allows you to search for an arbitrary number of strings.
|
||||
// Returns index of the target that is found first or -1 if timeout occurs.
|
||||
int findMulti(struct MultiTarget *targets, int tCount);
|
||||
};
|
||||
|
||||
#endif
|
||||
|
@ -195,7 +195,7 @@ String & String::copy(const __FlashStringHelper *pstr, unsigned int length)
|
||||
void String::move(String &rhs)
|
||||
{
|
||||
if (buffer) {
|
||||
if (rhs && capacity >= rhs.len) {
|
||||
if (capacity >= rhs.len) {
|
||||
strcpy(buffer, rhs.buffer);
|
||||
len = rhs.len;
|
||||
rhs.len = 0;
|
||||
|
@ -161,10 +161,6 @@ public:
|
||||
void toCharArray(char *buf, unsigned int bufsize, unsigned int index=0) const
|
||||
{getBytes((unsigned char *)buf, bufsize, index);}
|
||||
const char * c_str() const { return buffer; }
|
||||
char* begin() { return buffer; }
|
||||
char* end() { return buffer + length(); }
|
||||
const char* begin() const { return c_str(); }
|
||||
const char* end() const { return c_str() + length(); }
|
||||
|
||||
// search
|
||||
int indexOf( char ch ) const;
|
||||
|
@ -160,6 +160,4 @@ uint16 analogRead(uint8 pin);
|
||||
*/
|
||||
void shiftOut(uint8 dataPin, uint8 clockPin, uint8 bitOrder, uint8 value);
|
||||
|
||||
uint32 shiftIn( uint32 ulDataPin, uint32 ulClockPin, uint32 ulBitOrder );
|
||||
|
||||
#endif
|
||||
|
@ -120,12 +120,8 @@ extern char* ltoa( long value, char *string, int radix )
|
||||
|
||||
return string;
|
||||
}
|
||||
#if __GNUC__ > 4 || (__GNUC__ == 4 && (__GNUC_MINOR__ > 9 || \
|
||||
(__GNUC_MINOR__ == 9 && __GNUC_PATCHLEVEL__ > 2)))
|
||||
extern char* utoa( unsigned value, char *string, int radix )
|
||||
#else
|
||||
extern char* utoa( unsigned int value, char *string, int radix )
|
||||
#endif
|
||||
|
||||
extern char* utoa( unsigned long value, char *string, int radix )
|
||||
{
|
||||
return ultoa( value, string, radix ) ;
|
||||
}
|
||||
|
@ -31,12 +31,7 @@ extern void itoa( int n, char s[] ) ;
|
||||
|
||||
extern char* itoa( int value, char *string, int radix ) ;
|
||||
extern char* ltoa( long value, char *string, int radix ) ;
|
||||
#if __GNUC__ > 4 || (__GNUC__ == 4 && (__GNUC_MINOR__ > 9 || \
|
||||
(__GNUC_MINOR__ == 9 && __GNUC_PATCHLEVEL__ > 2)))
|
||||
extern char* utoa( unsigned value, char *string, int radix ) ;
|
||||
#else
|
||||
extern char* utoa( unsigned int value, char *string, int radix ) ;
|
||||
#endif
|
||||
extern char* utoa( unsigned long value, char *string, int radix ) ;
|
||||
extern char* ultoa( unsigned long value, char *string, int radix ) ;
|
||||
#endif /* 0 */
|
||||
|
||||
|
@ -59,7 +59,6 @@ void adc_set_extsel(adc_dev *dev, adc_extsel_event event) {
|
||||
uint32 cr2 = dev->regs->CR2;
|
||||
cr2 &= ~ADC_CR2_EXTSEL;
|
||||
cr2 |= event;
|
||||
cr2 |= ADC_CR2_EXTTRIG;
|
||||
dev->regs->CR2 = cr2;
|
||||
}
|
||||
|
||||
|
@ -341,6 +341,7 @@ void dma_set_per_addr(dma_dev *dev, dma_channel channel, __io void *addr) {
|
||||
* @see dma_attach_interrupt()
|
||||
* @see dma_enable()
|
||||
*/
|
||||
__deprecated
|
||||
void dma_setup_transfer(dma_dev *dev,
|
||||
dma_channel channel,
|
||||
__io void *peripheral_address,
|
||||
|
@ -142,6 +142,7 @@ gpio_pin_mode gpio_get_mode(gpio_dev *dev, uint8 pin) {
|
||||
gpio_reg_map *regs = dev->regs;
|
||||
__io uint32 *cr = ®s->CRL + (pin >> 3);
|
||||
uint32 shift = (pin & 0x7) * 4;
|
||||
uint32 tmp = *cr;
|
||||
|
||||
uint32 crMode = (*cr>>shift) & 0x0F;
|
||||
|
||||
|
@ -84,7 +84,7 @@ void spi_slave_enable(spi_dev *dev, spi_mode mode, uint32 flags) {
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Blocking SPI transmit.
|
||||
* @brief Nonblocking SPI transmit.
|
||||
* @param dev SPI port to use for transmission
|
||||
* @param buf Buffer to transmit. The sizeof buf's elements are
|
||||
* inferred from dev's data frame format (i.e., are
|
||||
@ -93,21 +93,15 @@ void spi_slave_enable(spi_dev *dev, spi_mode mode, uint32 flags) {
|
||||
* @return Number of elements transmitted.
|
||||
*/
|
||||
uint32 spi_tx(spi_dev *dev, const void *buf, uint32 len) {
|
||||
uint32 txed = len;
|
||||
spi_reg_map *regs = dev->regs;
|
||||
if ( spi_dff(dev) == SPI_DFF_8_BIT ) {
|
||||
const uint8 * dp8 = (const uint8*)buf;
|
||||
while ( len-- ) {
|
||||
while ( (regs->SR & SPI_SR_TXE)==0 ) ; //while ( spi_is_tx_empty(dev)==0 ); // wait Tx to be empty
|
||||
regs->DR = *dp8++;
|
||||
}
|
||||
} else {
|
||||
const uint16 * dp16 = (const uint16*)buf;
|
||||
while ( len-- ) {
|
||||
while ( (regs->SR & SPI_SR_TXE)==0 ) ; //while ( spi_is_tx_empty(dev)==0 ); // wait Tx to be empty
|
||||
regs->DR = *dp16++;
|
||||
}
|
||||
}
|
||||
uint32 txed = 0;
|
||||
uint8 byte_frame = spi_dff(dev) == SPI_DFF_8_BIT;
|
||||
while (spi_is_tx_empty(dev) && (txed < len)) {
|
||||
if (byte_frame) {
|
||||
dev->regs->DR = ((const uint8*)buf)[txed++];
|
||||
} else {
|
||||
dev->regs->DR = ((const uint16*)buf)[txed++];
|
||||
}
|
||||
}
|
||||
return txed;
|
||||
}
|
||||
|
||||
|
@ -199,20 +199,18 @@ void usart_foreach(void (*fn)(usart_dev*)) {
|
||||
/*
|
||||
* Interrupt handlers.
|
||||
*/
|
||||
|
||||
|
||||
void __irq_usart1(void) {
|
||||
usart_irq(&usart1_rb, &usart1_wb, USART1_BASE);
|
||||
}
|
||||
|
||||
/*
|
||||
void __irq_usart2(void) {
|
||||
usart_irq(&usart2_rb, &usart2_wb, USART2_BASE);
|
||||
}
|
||||
//void __irq_usart2(void) {
|
||||
// usart_irq(&usart2_rb, &usart2_wb, USART2_BASE);
|
||||
//}
|
||||
|
||||
void __irq_usart3(void) {
|
||||
usart_irq(&usart3_rb, &usart3_wb, USART3_BASE);
|
||||
}
|
||||
*/
|
||||
//void __irq_usart3(void) {
|
||||
// usart_irq(&usart3_rb, &usart3_wb, USART3_BASE);
|
||||
//}
|
||||
|
||||
#ifdef STM32_HIGH_DENSITY
|
||||
void __irq_uart4(void) {
|
||||
|
@ -62,8 +62,8 @@
|
||||
|
||||
#if !(defined(BOARD_maple) || defined(BOARD_maple_RET6) || \
|
||||
defined(BOARD_maple_mini) || defined(BOARD_maple_native))
|
||||
//#warning USB CDC ACM relies on LeafLabs board-specific configuration.\
|
||||
// You may have problems on non-LeafLabs boards.
|
||||
#warning USB CDC ACM relies on LeafLabs board-specific configuration.\
|
||||
You may have problems on non-LeafLabs boards.
|
||||
#endif
|
||||
|
||||
static void vcomDataTxCb(void);
|
||||
@ -261,28 +261,18 @@ static ONE_DESCRIPTOR String_Descriptor[N_STRING_DESCRIPTORS] = {
|
||||
|
||||
/* I/O state */
|
||||
|
||||
#define CDC_SERIAL_RX_BUFFER_SIZE 256 // must be power of 2
|
||||
#define CDC_SERIAL_RX_BUFFER_SIZE_MASK (CDC_SERIAL_RX_BUFFER_SIZE-1)
|
||||
#define CDC_SERIAL_BUFFER_SIZE 512
|
||||
|
||||
/* Received data */
|
||||
static volatile uint8 vcomBufferRx[CDC_SERIAL_RX_BUFFER_SIZE];
|
||||
/* Write index to vcomBufferRx */
|
||||
static volatile uint32 rx_head;
|
||||
/* Read index from vcomBufferRx */
|
||||
static volatile uint32 rx_tail;
|
||||
|
||||
#define CDC_SERIAL_TX_BUFFER_SIZE 256 // must be power of 2
|
||||
#define CDC_SERIAL_TX_BUFFER_SIZE_MASK (CDC_SERIAL_TX_BUFFER_SIZE-1)
|
||||
// Tx data
|
||||
static volatile uint8 vcomBufferTx[CDC_SERIAL_TX_BUFFER_SIZE];
|
||||
// Write index to vcomBufferTx
|
||||
static volatile uint32 tx_head;
|
||||
// Read index from vcomBufferTx
|
||||
static volatile uint32 tx_tail;
|
||||
// Are we currently sending an IN packet?
|
||||
static volatile int8 transmitting;
|
||||
|
||||
|
||||
static volatile uint8 vcomBufferRx[CDC_SERIAL_BUFFER_SIZE];
|
||||
/* Read index into vcomBufferRx */
|
||||
static volatile uint32 rx_offset = 0;
|
||||
/* Number of bytes left to transmit */
|
||||
static volatile uint32 n_unsent_bytes = 0;
|
||||
/* Are we currently sending an IN packet? */
|
||||
static volatile uint8 transmitting = 0;
|
||||
/* Number of unread bytes */
|
||||
static volatile uint32 n_unread_bytes = 0;
|
||||
|
||||
/* Other state (line coding, DTR/RTS) */
|
||||
|
||||
@ -384,13 +374,9 @@ void usb_cdcacm_enable(gpio_dev *disc_dev, uint8 disc_bit) {
|
||||
/* Present ourselves to the host. Writing 0 to "disc" pin must
|
||||
* pull USB_DP pin up while leaving USB_DM pulled down by the
|
||||
* transceiver. See USB 2.0 spec, section 7.1.7.3. */
|
||||
|
||||
if (disc_dev!=NULL)
|
||||
{
|
||||
gpio_set_mode(disc_dev, disc_bit, GPIO_OUTPUT_PP);
|
||||
gpio_write_bit(disc_dev, disc_bit, 0);
|
||||
}
|
||||
|
||||
gpio_set_mode(disc_dev, disc_bit, GPIO_OUTPUT_PP);
|
||||
gpio_write_bit(disc_dev, disc_bit, 0);
|
||||
|
||||
/* Initialize the USB peripheral. */
|
||||
usb_init_usblib(USBLIB, ep_int_in, ep_int_out);
|
||||
}
|
||||
@ -399,10 +385,7 @@ void usb_cdcacm_disable(gpio_dev *disc_dev, uint8 disc_bit) {
|
||||
/* Turn off the interrupt and signal disconnect (see e.g. USB 2.0
|
||||
* spec, section 7.1.7.3). */
|
||||
nvic_irq_disable(NVIC_USB_LP_CAN_RX0);
|
||||
if (disc_dev!=NULL)
|
||||
{
|
||||
gpio_write_bit(disc_dev, disc_bit, 1);
|
||||
}
|
||||
gpio_write_bit(disc_dev, disc_bit, 1);
|
||||
}
|
||||
|
||||
void usb_cdcacm_putc(char ch) {
|
||||
@ -410,34 +393,30 @@ void usb_cdcacm_putc(char ch) {
|
||||
;
|
||||
}
|
||||
|
||||
/* This function is non-blocking.
|
||||
/* This function is blocking.
|
||||
*
|
||||
* It copies data from a user buffer into the USB peripheral TX
|
||||
* It copies data from a usercode buffer into the USB peripheral TX
|
||||
* buffer, and returns the number of bytes copied. */
|
||||
uint32 usb_cdcacm_tx(const uint8* buf, uint32 len)
|
||||
{
|
||||
if (len==0) return 0; // no data to send
|
||||
uint32 usb_cdcacm_tx(const uint8* buf, uint32 len) {
|
||||
/* Last transmission hasn't finished, so abort. */
|
||||
while ( usb_cdcacm_is_transmitting()>0 ) ; // wait for end of transmission
|
||||
|
||||
uint32 head = tx_head; // load volatile variable
|
||||
uint32 tx_unsent = (head - tx_tail) & CDC_SERIAL_TX_BUFFER_SIZE_MASK;
|
||||
|
||||
// We can only put bytes in the buffer if there is place
|
||||
if (len > (CDC_SERIAL_TX_BUFFER_SIZE-tx_unsent-1) ) {
|
||||
len = (CDC_SERIAL_TX_BUFFER_SIZE-tx_unsent-1);
|
||||
/* We can only put USB_CDCACM_TX_EPSIZE bytes in the buffer. */
|
||||
if (len > USB_CDCACM_TX_EPSIZE) {
|
||||
len = USB_CDCACM_TX_EPSIZE;
|
||||
}
|
||||
if (len==0) return 0; // buffer full
|
||||
|
||||
uint16 i;
|
||||
// copy data from user buffer to USB Tx buffer
|
||||
for (i=0; i<len; i++) {
|
||||
vcomBufferTx[head] = buf[i];
|
||||
head = (head+1) & CDC_SERIAL_TX_BUFFER_SIZE_MASK;
|
||||
}
|
||||
tx_head = head; // store volatile variable
|
||||
|
||||
if (transmitting<0) {
|
||||
vcomDataTxCb(); // initiate data transmission
|
||||
}
|
||||
/* Queue bytes for sending. */
|
||||
if (len) {
|
||||
usb_copy_to_pma(buf, len, USB_CDCACM_TX_ADDR);
|
||||
}
|
||||
// We still need to wait for the interrupt, even if we're sending
|
||||
// zero bytes. (Sending zero-size packets is useful for flushing
|
||||
// host-side buffers.)
|
||||
usb_set_ep_tx_count(USB_CDCACM_TX_ENDP, len);
|
||||
n_unsent_bytes = len;
|
||||
transmitting = 1;
|
||||
usb_set_ep_tx_stat(USB_CDCACM_TX_ENDP, USB_EP_STAT_TX_VALID);
|
||||
|
||||
return len;
|
||||
}
|
||||
@ -445,73 +424,69 @@ uint32 usb_cdcacm_tx(const uint8* buf, uint32 len)
|
||||
|
||||
|
||||
uint32 usb_cdcacm_data_available(void) {
|
||||
return (rx_head - rx_tail) & CDC_SERIAL_RX_BUFFER_SIZE_MASK;
|
||||
return n_unread_bytes;
|
||||
}
|
||||
|
||||
uint8 usb_cdcacm_is_transmitting(void) {
|
||||
return ( transmitting>0 ? transmitting : 0);
|
||||
return transmitting;
|
||||
}
|
||||
|
||||
uint16 usb_cdcacm_get_pending(void) {
|
||||
return (tx_head - tx_tail) & CDC_SERIAL_TX_BUFFER_SIZE_MASK;
|
||||
return n_unsent_bytes;
|
||||
}
|
||||
|
||||
/* Non-blocking byte receive.
|
||||
/* Nonblocking byte receive.
|
||||
*
|
||||
* Copies up to len bytes from our private data buffer (*NOT* the PMA)
|
||||
* into buf and deq's the FIFO. */
|
||||
uint32 usb_cdcacm_rx(uint8* buf, uint32 len)
|
||||
{
|
||||
uint32 usb_cdcacm_rx(uint8* buf, uint32 len) {
|
||||
/* Copy bytes to buffer. */
|
||||
uint32 n_copied = usb_cdcacm_peek(buf, len);
|
||||
|
||||
/* Mark bytes as read. */
|
||||
uint16 tail = rx_tail; // load volatile variable
|
||||
tail = (tail + n_copied) & CDC_SERIAL_RX_BUFFER_SIZE_MASK;
|
||||
rx_tail = tail; // store volatile variable
|
||||
n_unread_bytes -= n_copied;
|
||||
rx_offset = (rx_offset + n_copied) % CDC_SERIAL_BUFFER_SIZE;
|
||||
|
||||
uint32 rx_unread = (rx_head - tail) & CDC_SERIAL_RX_BUFFER_SIZE_MASK;
|
||||
// If buffer was emptied to a pre-set value, re-enable the RX endpoint
|
||||
if ( rx_unread <= 64 ) { // experimental value, gives the best performance
|
||||
/* If all bytes have been read, re-enable the RX endpoint, which
|
||||
* was set to NAK when the current batch of bytes was received. */
|
||||
if (n_unread_bytes == 0) {
|
||||
usb_set_ep_rx_count(USB_CDCACM_RX_ENDP, USB_CDCACM_RX_EPSIZE);
|
||||
usb_set_ep_rx_stat(USB_CDCACM_RX_ENDP, USB_EP_STAT_RX_VALID);
|
||||
}
|
||||
}
|
||||
|
||||
return n_copied;
|
||||
}
|
||||
|
||||
/* Non-blocking byte lookahead.
|
||||
/* Nonblocking byte lookahead.
|
||||
*
|
||||
* Looks at unread bytes without marking them as read. */
|
||||
uint32 usb_cdcacm_peek(uint8* buf, uint32 len)
|
||||
{
|
||||
uint32 usb_cdcacm_peek(uint8* buf, uint32 len) {
|
||||
int i;
|
||||
uint32 tail = rx_tail;
|
||||
uint32 rx_unread = (rx_head-tail) & CDC_SERIAL_RX_BUFFER_SIZE_MASK;
|
||||
uint32 head = rx_offset;
|
||||
|
||||
if (len > rx_unread) {
|
||||
len = rx_unread;
|
||||
if (len > n_unread_bytes) {
|
||||
len = n_unread_bytes;
|
||||
}
|
||||
|
||||
for (i = 0; i < len; i++) {
|
||||
buf[i] = vcomBufferRx[tail];
|
||||
tail = (tail + 1) & CDC_SERIAL_RX_BUFFER_SIZE_MASK;
|
||||
buf[i] = vcomBufferRx[head];
|
||||
head = (head + 1) % CDC_SERIAL_BUFFER_SIZE;
|
||||
}
|
||||
|
||||
return len;
|
||||
}
|
||||
|
||||
uint32 usb_cdcacm_peek_ex(uint8* buf, uint32 offset, uint32 len)
|
||||
{
|
||||
uint32 usb_cdcacm_peek_ex(uint8* buf, uint32 offset, uint32 len) {
|
||||
int i;
|
||||
uint32 tail = (rx_tail + offset) & CDC_SERIAL_RX_BUFFER_SIZE_MASK ;
|
||||
uint32 rx_unread = (rx_head-tail) & CDC_SERIAL_RX_BUFFER_SIZE_MASK;
|
||||
uint32 head = (rx_offset + offset) % CDC_SERIAL_BUFFER_SIZE;
|
||||
|
||||
if (len + offset > rx_unread) {
|
||||
len = rx_unread - offset;
|
||||
if (len + offset > n_unread_bytes) {
|
||||
len = n_unread_bytes - offset;
|
||||
}
|
||||
|
||||
for (i = 0; i < len; i++) {
|
||||
buf[i] = vcomBufferRx[tail];
|
||||
tail = (tail + 1) & CDC_SERIAL_RX_BUFFER_SIZE_MASK;
|
||||
buf[i] = vcomBufferRx[head];
|
||||
head = (head + 1) % CDC_SERIAL_BUFFER_SIZE;
|
||||
}
|
||||
|
||||
return len;
|
||||
@ -520,12 +495,12 @@ uint32 usb_cdcacm_peek_ex(uint8* buf, uint32 offset, uint32 len)
|
||||
/* Roger Clark. Added. for Arduino 1.0 API support of Serial.peek() */
|
||||
int usb_cdcacm_peek_char()
|
||||
{
|
||||
if (usb_cdcacm_data_available() == 0)
|
||||
if (n_unread_bytes == 0)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
return vcomBufferRx[rx_tail];
|
||||
return vcomBufferRx[rx_offset];
|
||||
}
|
||||
|
||||
uint8 usb_cdcacm_get_dtr() {
|
||||
@ -559,76 +534,42 @@ int usb_cdcacm_get_n_data_bits(void) {
|
||||
return line_coding.bDataBits;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Callbacks
|
||||
*/
|
||||
static void vcomDataTxCb(void)
|
||||
{
|
||||
uint32 tail = tx_tail; // load volatile variable
|
||||
uint32 tx_unsent = (tx_head - tail) & CDC_SERIAL_TX_BUFFER_SIZE_MASK;
|
||||
if (tx_unsent==0) {
|
||||
if ( (--transmitting)==0) goto flush; // no more data to send
|
||||
return; // it was already flushed, keep Tx endpoint disabled
|
||||
}
|
||||
transmitting = 1;
|
||||
// We can only send up to USB_CDCACM_TX_EPSIZE bytes in the endpoint.
|
||||
if (tx_unsent > USB_CDCACM_TX_EPSIZE) {
|
||||
tx_unsent = USB_CDCACM_TX_EPSIZE;
|
||||
}
|
||||
// copy the bytes from USB Tx buffer to PMA buffer
|
||||
uint32 *dst = usb_pma_ptr(USB_CDCACM_TX_ADDR);
|
||||
uint16 tmp = 0;
|
||||
uint16 val;
|
||||
int i;
|
||||
for (i = 0; i < tx_unsent; i++) {
|
||||
val = vcomBufferTx[tail];
|
||||
tail = (tail + 1) & CDC_SERIAL_TX_BUFFER_SIZE_MASK;
|
||||
if (i&1) {
|
||||
*dst++ = tmp | (val<<8);
|
||||
} else {
|
||||
tmp = val;
|
||||
}
|
||||
}
|
||||
if ( tx_unsent&1 ) {
|
||||
*dst = tmp;
|
||||
}
|
||||
tx_tail = tail; // store volatile variable
|
||||
flush:
|
||||
// enable Tx endpoint
|
||||
usb_set_ep_tx_count(USB_CDCACM_TX_ENDP, tx_unsent);
|
||||
usb_set_ep_tx_stat(USB_CDCACM_TX_ENDP, USB_EP_STAT_TX_VALID);
|
||||
|
||||
static void vcomDataTxCb(void) {
|
||||
n_unsent_bytes = 0;
|
||||
transmitting = 0;
|
||||
}
|
||||
|
||||
|
||||
static void vcomDataRxCb(void)
|
||||
{
|
||||
uint32 head = rx_head; // load volatile variable
|
||||
|
||||
uint32 ep_rx_size = usb_get_ep_rx_count(USB_CDCACM_RX_ENDP);
|
||||
// This copy won't overwrite unread bytes as long as there is
|
||||
// enough room in the USB Rx buffer for next packet
|
||||
uint32 *src = usb_pma_ptr(USB_CDCACM_RX_ADDR);
|
||||
uint16 tmp = 0;
|
||||
uint8 val;
|
||||
static void vcomDataRxCb(void) {
|
||||
uint32 ep_rx_size;
|
||||
uint32 tail = (rx_offset + n_unread_bytes) % CDC_SERIAL_BUFFER_SIZE;
|
||||
uint8 ep_rx_data[USB_CDCACM_RX_EPSIZE];
|
||||
uint32 i;
|
||||
for (i = 0; i < ep_rx_size; i++) {
|
||||
if (i&1) {
|
||||
val = tmp>>8;
|
||||
} else {
|
||||
tmp = *src++;
|
||||
val = tmp&0xFF;
|
||||
}
|
||||
vcomBufferRx[head] = val;
|
||||
head = (head + 1) & CDC_SERIAL_RX_BUFFER_SIZE_MASK;
|
||||
}
|
||||
rx_head = head; // store volatile variable
|
||||
|
||||
uint32 rx_unread = (head - rx_tail) & CDC_SERIAL_RX_BUFFER_SIZE_MASK;
|
||||
// only enable further Rx if there is enough room to receive one more packet
|
||||
if ( rx_unread < (CDC_SERIAL_RX_BUFFER_SIZE-USB_CDCACM_RX_EPSIZE) ) {
|
||||
usb_set_ep_rx_stat(USB_CDCACM_RX_ENDP, USB_EP_STAT_RX_VALID);
|
||||
usb_set_ep_rx_stat(USB_CDCACM_RX_ENDP, USB_EP_STAT_RX_NAK);
|
||||
ep_rx_size = usb_get_ep_rx_count(USB_CDCACM_RX_ENDP);
|
||||
/* This copy won't overwrite unread bytes, since we've set the RX
|
||||
* endpoint to NAK, and will only set it to VALID when all bytes
|
||||
* have been read. */
|
||||
usb_copy_from_pma((uint8*)ep_rx_data, ep_rx_size,
|
||||
USB_CDCACM_RX_ADDR);
|
||||
|
||||
for (i = 0; i < ep_rx_size; i++) {
|
||||
vcomBufferRx[tail] = ep_rx_data[i];
|
||||
tail = (tail + 1) % CDC_SERIAL_BUFFER_SIZE;
|
||||
}
|
||||
|
||||
n_unread_bytes += ep_rx_size;
|
||||
|
||||
if ( n_unread_bytes == 0 ) {
|
||||
usb_set_ep_rx_count(USB_CDCACM_RX_ENDP, USB_CDCACM_RX_EPSIZE);
|
||||
usb_set_ep_rx_stat(USB_CDCACM_RX_ENDP, USB_EP_STAT_RX_VALID);
|
||||
}
|
||||
|
||||
if (rx_hook) {
|
||||
rx_hook(USB_CDCACM_HOOK_RX, 0);
|
||||
}
|
||||
@ -705,11 +646,10 @@ static void usbReset(void) {
|
||||
SetDeviceAddress(0);
|
||||
|
||||
/* Reset the RX/TX state */
|
||||
rx_head = 0;
|
||||
rx_tail = 0;
|
||||
tx_head = 0;
|
||||
tx_tail = 0;
|
||||
transmitting = -1;
|
||||
n_unread_bytes = 0;
|
||||
n_unsent_bytes = 0;
|
||||
rx_offset = 0;
|
||||
transmitting = 0;
|
||||
}
|
||||
|
||||
static RESULT usbDataSetup(uint8 request) {
|
||||
|
@ -29,7 +29,7 @@
|
||||
/* TODO these could use some improvement; they're fairly
|
||||
* straightforward ports of the analogous ST code. The PMA blit
|
||||
* routines in particular are obvious targets for performance
|
||||
* measurement and tuning.
|
||||
* measurement and tuning. */
|
||||
|
||||
void usb_copy_to_pma(const uint8 *buf, uint16 len, uint16 pma_offset) {
|
||||
uint16 *dst = (uint16*)usb_pma_ptr(pma_offset);
|
||||
@ -57,7 +57,7 @@ void usb_copy_from_pma(uint8 *buf, uint16 len, uint16 pma_offset) {
|
||||
*dst = *src & 0xFF;
|
||||
}
|
||||
}
|
||||
*/
|
||||
|
||||
static void usb_set_ep_rx_count_common(uint32 *rxc, uint16 count) {
|
||||
uint16 nblocks;
|
||||
if (count > 62) {
|
||||
@ -76,12 +76,12 @@ static void usb_set_ep_rx_count_common(uint32 *rxc, uint16 count) {
|
||||
*rxc = nblocks << 10;
|
||||
}
|
||||
}
|
||||
/*
|
||||
|
||||
void usb_set_ep_rx_buf0_count(uint8 ep, uint16 count) {
|
||||
uint32 *rxc = usb_ep_rx_buf0_count_ptr(ep);
|
||||
usb_set_ep_rx_count_common(rxc, count);
|
||||
}
|
||||
*/
|
||||
|
||||
void usb_set_ep_rx_count(uint8 ep, uint16 count) {
|
||||
uint32 *rxc = usb_ep_rx_count_ptr(ep);
|
||||
usb_set_ep_rx_count_common(rxc, count);
|
||||
|
@ -1,36 +0,0 @@
|
||||
/*
|
||||
Copyright (c) 2014 Arduino. All right reserved.
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
See the GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public
|
||||
License along with this library; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*/
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
void *operator new(size_t size) {
|
||||
return malloc(size);
|
||||
}
|
||||
|
||||
void *operator new[](size_t size) {
|
||||
return malloc(size);
|
||||
}
|
||||
|
||||
void operator delete(void * ptr) {
|
||||
free(ptr);
|
||||
}
|
||||
|
||||
void operator delete[](void * ptr) {
|
||||
free(ptr);
|
||||
}
|
||||
|
@ -1,198 +0,0 @@
|
||||
/******************************************************************************
|
||||
* 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 libmaple/sdio.c
|
||||
* @author stevstrong
|
||||
* @brief Secure digital input/output interface.
|
||||
*/
|
||||
|
||||
#include <libmaple/sdio.h>
|
||||
#include <libmaple/gpio.h>
|
||||
#include <boards.h>
|
||||
#include "wirish.h"
|
||||
|
||||
|
||||
//#include <libmaple/libmaple.h>
|
||||
//#include <libmaple/rcc.h>
|
||||
//#include <series/gpio.h>
|
||||
//#include "wirish.h"
|
||||
//#include "boards.h"
|
||||
//
|
||||
|
||||
#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
|
||||
|
||||
sdio_dev * SDIO = SDIO_BASE;
|
||||
|
||||
#define DELAY_LONG 10
|
||||
#define DELAY_SHORT 1
|
||||
|
||||
uint8_t dly = DELAY_LONG; // microseconds delay after accessing registers
|
||||
|
||||
/*
|
||||
* SDIO convenience routines
|
||||
*/
|
||||
void sdio_gpios_init(void)
|
||||
{
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_D0].gpio_device, PIN_MAP[BOARD_SDIO_D0].gpio_bit, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_D1].gpio_device, PIN_MAP[BOARD_SDIO_D1].gpio_bit, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_D2].gpio_device, PIN_MAP[BOARD_SDIO_D2].gpio_bit, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_D3].gpio_device, PIN_MAP[BOARD_SDIO_D3].gpio_bit, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_CLK].gpio_device, PIN_MAP[BOARD_SDIO_CLK].gpio_bit, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_CMD].gpio_device, PIN_MAP[BOARD_SDIO_CMD].gpio_bit, GPIO_AF_OUTPUT_PP);
|
||||
/*
|
||||
* Todo just remove it, not needed for F1.
|
||||
*/
|
||||
/*
|
||||
gpio_set_af_mode(BOARD_SDIO_D0, 12);
|
||||
gpio_set_af_mode(BOARD_SDIO_D1, 12);
|
||||
gpio_set_af_mode(BOARD_SDIO_D2, 12);
|
||||
gpio_set_af_mode(BOARD_SDIO_D3, 12);
|
||||
gpio_set_af_mode(BOARD_SDIO_CLK, 12);
|
||||
gpio_set_af_mode(BOARD_SDIO_CMD, 12);
|
||||
*/
|
||||
}
|
||||
|
||||
void sdio_gpios_deinit(void)
|
||||
{
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_D0].gpio_device, PIN_MAP[BOARD_SDIO_D0].gpio_bit, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_D1].gpio_device, PIN_MAP[BOARD_SDIO_D1].gpio_bit, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_D2].gpio_device, PIN_MAP[BOARD_SDIO_D2].gpio_bit, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_D3].gpio_device, PIN_MAP[BOARD_SDIO_D3].gpio_bit, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_CLK].gpio_device, PIN_MAP[BOARD_SDIO_CLK].gpio_bit, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(PIN_MAP[BOARD_SDIO_CMD].gpio_device, PIN_MAP[BOARD_SDIO_CMD].gpio_bit, GPIO_INPUT_FLOATING);
|
||||
|
||||
/*
|
||||
* Todo just remove it, not needed for F1.
|
||||
*/
|
||||
/*
|
||||
gpio_set_af_mode(BOARD_SDIO_D0, 0);
|
||||
gpio_set_af_mode(BOARD_SDIO_D1, 0);
|
||||
gpio_set_af_mode(BOARD_SDIO_D2, 0);
|
||||
gpio_set_af_mode(BOARD_SDIO_D3, 0);
|
||||
gpio_set_af_mode(BOARD_SDIO_CLK, 0);
|
||||
gpio_set_af_mode(BOARD_SDIO_CMD, 0);
|
||||
*/
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initialize and reset the SDIO device.
|
||||
*/
|
||||
void sdio_init(void)
|
||||
{
|
||||
rcc_clk_enable(RCC_SDIO);
|
||||
rcc_reset_dev(RCC_SDIO);
|
||||
}
|
||||
|
||||
void sdio_power_on(void)
|
||||
{
|
||||
SDIO->POWER = SDIO_POWER_PWRCTRL_ON;
|
||||
// After a data write, data cannot be written to this register for three SDIOCLK clock periods
|
||||
// plus two PCLK2 clock periods.
|
||||
delay_us(DELAY_LONG);
|
||||
}
|
||||
|
||||
void sdio_power_off(void)
|
||||
{
|
||||
SDIO->POWER = SDIO_POWER_PWRCTRL_OFF;
|
||||
// After a data write, data cannot be written to this register for three SDIOCLK clock periods
|
||||
// plus two PCLK2 clock periods.
|
||||
delay_us(DELAY_LONG);
|
||||
}
|
||||
|
||||
void sdio_set_clock(uint32_t clk)
|
||||
{
|
||||
if (clk>24000000UL) clk = 24000000UL; // limit the SDIO master clock to 24MHz
|
||||
|
||||
if (clk<1000000) dly = DELAY_LONG;
|
||||
else dly = DELAY_SHORT;
|
||||
|
||||
sdio_disable();
|
||||
SDIO->CLKCR = (SDIO->CLKCR & (~(SDIO_CLKCR_CLKDIV|SDIO_CLKCR_BYPASS))) | SDIO_CLKCR_CLKEN | (((SDIOCLK/clk)-2)&SDIO_CLKCR_CLKDIV);
|
||||
delay_us(dly);
|
||||
}
|
||||
|
||||
void sdio_set_dbus_width(uint16_t bus_w)
|
||||
{
|
||||
SDIO->CLKCR = (SDIO->CLKCR & (~SDIO_CLKCR_WIDBUS)) | bus_w;
|
||||
delay_us(dly);
|
||||
}
|
||||
|
||||
void sdio_set_dblock_size(uint8_t dbsize)
|
||||
{
|
||||
SDIO->DCTRL = (SDIO->DCTRL&(~SDIO_DCTRL_DBLOCKSIZE)) | ((dbsize&0xF)<<4);
|
||||
delay_us(dly);
|
||||
}
|
||||
|
||||
void sdio_enable(void)
|
||||
{
|
||||
SDIO->CLKCR |= SDIO_CLKCR_CLKEN;
|
||||
delay_us(dly);
|
||||
}
|
||||
|
||||
void sdio_disable(void)
|
||||
{
|
||||
SDIO->CLKCR ^= SDIO_CLKCR_CLKEN;
|
||||
delay_us(dly);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Configure and enable the SDIO device.
|
||||
*/
|
||||
void sdio_begin(void)
|
||||
{
|
||||
sdio_gpios_init();
|
||||
sdio_init();
|
||||
sdio_power_on();
|
||||
// Set initial SCK rate.
|
||||
sdio_set_clock(400000);
|
||||
delay_us(200); // generate 80 pulses at 400kHz
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Disables the SDIO device.
|
||||
*/
|
||||
void sdio_end(void)
|
||||
{
|
||||
sdio_disable();
|
||||
while ( sdio_cmd_xfer_ongoing() );
|
||||
sdio_power_off();
|
||||
rcc_clk_disable(RCC_SDIO);
|
||||
sdio_gpios_deinit();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send command by the SDIO device.
|
||||
*/
|
||||
uint8_t sdio_cmd_send(uint16_t cmd_index_resp_type, uint32_t arg)
|
||||
{
|
||||
uint8_t retries = 10; // in case of errors
|
||||
do { // retry command if errors detected
|
||||
// clear interrupt flags - IMPORTANT!!!
|
||||
SDIO->ICR = SDIO_ICR_CMD_FLAGS;
|
||||
// write command
|
||||
SDIO->ARG = arg;
|
||||
SDIO->CMD = (uint32_t)(SDIO_CMD_CPSMEN | cmd_index_resp_type );
|
||||
while ( (SDIO->STA&SDIO_STA_CMDACT) ) ; // wait for actual command transfer to finish
|
||||
// wait for response, if the case
|
||||
if ( cmd_index_resp_type&(SDIO_CMD_WAIT_SHORT_RESP|SDIO_CMD_WAIT_LONG_RESP) ) {
|
||||
while ( !(SDIO->STA&(SDIO_STA_CMDREND|SDIO_STA_CMD_ERROR_FLAGS)) ) ;
|
||||
} else break; // no response required
|
||||
if ( SDIO->STA&(SDIO_STA_CMDREND|SDIO_STA_CTIMEOUT) )
|
||||
break; // response received or timeout
|
||||
// ignore CRC error for CMD5 and ACMD41
|
||||
if ( ((cmd_index_resp_type&SDIO_CMD_CMDINDEX)==5) || ((cmd_index_resp_type&SDIO_CMD_CMDINDEX)==41) )
|
||||
break;
|
||||
} while ( (--retries) );
|
||||
return (uint8_t)retries;
|
||||
}
|
||||
|
||||
#endif // defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
|
@ -80,13 +80,10 @@ void pinMode(uint8 pin, WiringPinMode mode) {
|
||||
gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit, outputMode);
|
||||
|
||||
if (PIN_MAP[pin].timer_device != NULL) {
|
||||
if ( pwm ) { // we're switching into PWM, enable timer channels
|
||||
/* Enable/disable timer channels if we're switching into or
|
||||
* out of PWM. */
|
||||
timer_set_mode(PIN_MAP[pin].timer_device,
|
||||
PIN_MAP[pin].timer_channel,
|
||||
TIMER_PWM );
|
||||
} else { // disable channel output in non pwm-Mode
|
||||
timer_cc_disable(PIN_MAP[pin].timer_device,
|
||||
PIN_MAP[pin].timer_channel);
|
||||
}
|
||||
pwm ? TIMER_PWM : TIMER_DISABLED);
|
||||
}
|
||||
}
|
||||
|
@ -1,204 +0,0 @@
|
||||
///////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// tone(pin,frequency[,duration]) generate a tone on a given pin
|
||||
//
|
||||
// noTone(pin) switch off the tone on the pin
|
||||
//
|
||||
// setToneTimerChannel(timer,channel) force use of given timer/channel
|
||||
//
|
||||
///////////////////////////////////////////////////////////////////////
|
||||
|
||||
#include "Arduino.h"
|
||||
#include <HardwareTimer.h>
|
||||
|
||||
|
||||
#define PinTimer(pin) (PIN_MAP[pin].timer_device->clk_id-RCC_TIMER1+1)
|
||||
#define PinChannel(pin) (PIN_MAP[pin].timer_channel)
|
||||
|
||||
// if USE_PIN_TIMER is set, the PWM timer/channel is used for PWM pins
|
||||
#define USE_PIN_TIMER
|
||||
|
||||
// if USE_BSRR is set the tone pin will be written via the fast BSRR register
|
||||
// instead of using the slow digitalWrite() function in the interrupt handler
|
||||
#define USE_BSRR
|
||||
|
||||
// construct static timer array (
|
||||
|
||||
|
||||
#ifdef STM32_HIGH_DENSITY
|
||||
// define default timer and channel
|
||||
#ifndef TONE_TIMER
|
||||
#define TONE_TIMER 8
|
||||
#endif
|
||||
#ifndef TONE_CHANNEL
|
||||
#define TONE_CHANNEL 8
|
||||
#endif
|
||||
|
||||
HardwareTimer TTimer1(1), TTimer2(2), TTimer3(3), TTimer4(4),TTimer5(5), TTimer6(6), TTimer7(7), TTimer8(8);
|
||||
HardwareTimer *TTimer[8] = { &TTimer1,&TTimer2,&TTimer3,&TTimer4,&TTimer5,&TTimer6,&TTimer7,&TTimer8 };
|
||||
#else
|
||||
// define default timer and channel
|
||||
#ifndef TONE_TIMER
|
||||
#define TONE_TIMER 4
|
||||
#endif
|
||||
#ifndef TONE_CHANNEL
|
||||
#define TONE_CHANNEL 4
|
||||
#endif
|
||||
|
||||
HardwareTimer TTimer1(1), TTimer2(2), TTimer3(3), TTimer4(4);
|
||||
HardwareTimer *TTimer[4] = { &TTimer1,&TTimer2,&TTimer3,&TTimer4 };
|
||||
#endif
|
||||
|
||||
|
||||
uint8_t tone_force_channel = 0; // forced timer channel
|
||||
uint8_t tone_force_ntimer = 0; // forced timer
|
||||
|
||||
HardwareTimer *tone_timer;// = TTimer[TONE_TIMER-1]; // timer used to generate frequency
|
||||
uint8_t tone_channel = TONE_CHANNEL; // timer channel used to generate frequency
|
||||
uint8_t tone_ntimer = TONE_TIMER; // timer used to generate frequency
|
||||
|
||||
bool tone_state = true; // last pin state for toggling
|
||||
short tone_pin = -1; // pin for outputting sound
|
||||
short tone_freq = 444; // tone frequency (0=pause)
|
||||
volatile uint32_t tone_nhw = 0; // tone duration in number of half waves
|
||||
uint16_t tone_tcount = 0; // time between handler calls in 1/36 usec
|
||||
uint16_t tone_ncount = 0; // handler call between toggling
|
||||
uint16_t tone_n = 0; // remaining handler calls before toggling
|
||||
uint32_t tone_next = 0; // counter value of next interrupt
|
||||
|
||||
#ifdef USE_BSRR
|
||||
volatile uint32_t *tone_bsrr; // BSRR set register (lower 16 bits)
|
||||
uint32_t tone_smask=0; // BSRR set bitmask
|
||||
uint32_t tone_rmask=0; // BSRR reset bitmask
|
||||
#endif
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// timer hander for tone with no duration specified,
|
||||
// will keep going until noTone() is called
|
||||
void tone_handler_1(void) {
|
||||
tone_next += tone_tcount; // comparator value for next interrupt
|
||||
tone_timer->setCompare(tone_channel, tone_next); // and install it
|
||||
if(--tone_n == 0){
|
||||
tone_state = !tone_state; // toggle tone output
|
||||
|
||||
#ifdef USE_BSRR
|
||||
if(tone_state)
|
||||
*tone_bsrr = tone_smask;
|
||||
else
|
||||
*tone_bsrr = tone_rmask;
|
||||
#else
|
||||
digitalWrite(tone_pin,tone_state);// and output it
|
||||
#endif
|
||||
|
||||
tone_n = tone_ncount; // reset interrupt counter
|
||||
}
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// timer hander for tone with a specified duration,
|
||||
// will stop automatically when duration time is up.
|
||||
void tone_handler_2(void) {
|
||||
tone_next += tone_tcount;
|
||||
tone_timer->setCompare(tone_channel, tone_next);
|
||||
if(--tone_n == 0){
|
||||
if(tone_freq>0){ // toggle pin
|
||||
tone_state = !tone_state;
|
||||
#ifdef USE_BSRR
|
||||
if(tone_state)
|
||||
*tone_bsrr = tone_smask;
|
||||
else
|
||||
*tone_bsrr = tone_rmask;
|
||||
#else
|
||||
digitalWrite(tone_pin,tone_state);// and output it
|
||||
#endif
|
||||
}
|
||||
tone_n = tone_ncount;
|
||||
if(!--tone_nhw){ // check if tone duration has finished
|
||||
tone_timer->pause(); // disable timer
|
||||
pinMode(tone_pin, INPUT); // disable tone pin
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// play a tone on given pin with given frequency and optional duration in msec
|
||||
void tone(uint32_t pin, uint32_t freq, uint32_t duration) {
|
||||
tone_pin = pin;
|
||||
|
||||
#ifdef USE_PIN_TIMER
|
||||
// if the pin has a PWM timer/channel, use it (unless the timer/channel are forced)
|
||||
if(PinChannel(tone_pin) && !tone_force_channel){
|
||||
tone_channel = PinChannel(tone_pin);
|
||||
tone_ntimer = PinTimer(tone_pin);
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
// set timer and channel to default resp values forced with setToneTimerChannel
|
||||
tone_ntimer = tone_force_channel?tone_force_ntimer:TONE_TIMER;
|
||||
tone_channel = tone_force_channel?tone_force_channel:TONE_CHANNEL;
|
||||
}
|
||||
|
||||
tone_timer = TTimer[tone_ntimer-1];
|
||||
tone_freq = freq;
|
||||
tone_nhw = 0;
|
||||
tone_next = 0;
|
||||
|
||||
tone_timer->pause();
|
||||
|
||||
if(freq > 0){
|
||||
uint32_t count = (F_CPU/4)/freq; // timer counts per half wave
|
||||
tone_ncount = tone_n = (count>>16)+1; // number of 16-bit count chunk
|
||||
tone_tcount = count/tone_ncount; // size of count chunk
|
||||
if(duration > 0) // number of half waves to be generated
|
||||
tone_nhw = ((duration*freq)/1000)<<1;
|
||||
else // no duration specified, continuous sound until noTone() called
|
||||
tone_nhw = 0;
|
||||
|
||||
pinMode(tone_pin, PWM); // configure output pin
|
||||
pinMode(tone_pin, OUTPUT); // configure output pin
|
||||
|
||||
#ifdef USE_BSRR
|
||||
// Set up BSRR register values for fast ISR
|
||||
tone_bsrr = &((PIN_MAP[tone_pin].gpio_device)->regs->BSRR);
|
||||
tone_smask = (BIT(PIN_MAP[tone_pin].gpio_bit));
|
||||
tone_rmask = tone_smask<<16;
|
||||
#endif
|
||||
|
||||
// Set up an interrupt on given timer and channel
|
||||
tone_next = tone_tcount; // prepare channel compare register
|
||||
tone_timer->setMode(tone_channel,TIMER_OUTPUT_COMPARE);
|
||||
tone_timer->setCompare(tone_channel,tone_next);
|
||||
// attach corresponding handler routine
|
||||
tone_timer->attachInterrupt(tone_channel,tone_nhw?tone_handler_2:tone_handler_1);
|
||||
|
||||
// Refresh the tone timer
|
||||
tone_timer->refresh();
|
||||
|
||||
// Start the timer counting
|
||||
tone_timer->resume();
|
||||
|
||||
} else {
|
||||
|
||||
// detach handler routine
|
||||
tone_timer->detachInterrupt(tone_channel);
|
||||
// disactive pin by configuring it as input
|
||||
pinMode(tone_pin, INPUT);
|
||||
|
||||
}
|
||||
while(tone_nhw) ; // blocks till duration elapsed
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// disable tone on specified pin, if any
|
||||
void noTone(uint32_t pin){
|
||||
tone(pin,0,0); // it's all handled in tone()
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// set timer and channel to some different value
|
||||
// must be called before calling tone() or after noTone() was called
|
||||
void setToneTimerChannel(uint8_t ntimer, uint8_t channel){
|
||||
tone_force_ntimer = ntimer;
|
||||
tone_force_channel = channel;
|
||||
}
|
@ -1,28 +0,0 @@
|
||||
/*
|
||||
Copyright (c) 2015 Arduino LLC. All right reserved.
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
See the GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public
|
||||
License along with this library; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
#include "Arduino.h"
|
||||
|
||||
void tone(uint32_t _pin, uint32_t frequency, uint32_t duration = 0);
|
||||
void noTone(uint32_t _pin);
|
||||
|
||||
#endif
|
@ -54,9 +54,6 @@ static void ifaceSetupHook(unsigned, void*);
|
||||
*/
|
||||
|
||||
#define USB_TIMEOUT 50
|
||||
#if BOARD_HAVE_SERIALUSB
|
||||
bool USBSerial::_hasBegun = false;
|
||||
#endif
|
||||
|
||||
USBSerial::USBSerial(void) {
|
||||
#if !BOARD_HAVE_SERIALUSB
|
||||
@ -65,13 +62,8 @@ USBSerial::USBSerial(void) {
|
||||
}
|
||||
|
||||
void USBSerial::begin(void) {
|
||||
|
||||
#if BOARD_HAVE_SERIALUSB
|
||||
if (_hasBegun)
|
||||
return;
|
||||
_hasBegun = true;
|
||||
|
||||
usb_cdcacm_enable(BOARD_USB_DISC_DEV, (uint8_t)BOARD_USB_DISC_BIT);
|
||||
usb_cdcacm_enable(BOARD_USB_DISC_DEV, BOARD_USB_DISC_BIT);
|
||||
usb_cdcacm_set_hooks(USB_CDCACM_HOOK_RX, rxHook);
|
||||
usb_cdcacm_set_hooks(USB_CDCACM_HOOK_IFACE_SETUP, ifaceSetupHook);
|
||||
#endif
|
||||
@ -83,7 +75,6 @@ void USBSerial::begin(unsigned long ignoreBaud)
|
||||
volatile unsigned long removeCompilerWarningsIgnoreBaud=ignoreBaud;
|
||||
|
||||
ignoreBaud=removeCompilerWarningsIgnoreBaud;
|
||||
begin();
|
||||
}
|
||||
void USBSerial::begin(unsigned long ignoreBaud, uint8_t ignore)
|
||||
{
|
||||
@ -92,16 +83,13 @@ volatile uint8_t removeCompilerWarningsIgnore=ignore;
|
||||
|
||||
ignoreBaud=removeCompilerWarningsIgnoreBaud;
|
||||
ignore=removeCompilerWarningsIgnore;
|
||||
begin();
|
||||
}
|
||||
|
||||
void USBSerial::end(void) {
|
||||
#if BOARD_HAVE_SERIALUSB
|
||||
usb_cdcacm_disable(BOARD_USB_DISC_DEV, (uint8_t)BOARD_USB_DISC_BIT);
|
||||
usb_cdcacm_disable(BOARD_USB_DISC_DEV, BOARD_USB_DISC_BIT);
|
||||
usb_cdcacm_remove_hooks(USB_CDCACM_HOOK_RX | USB_CDCACM_HOOK_IFACE_SETUP);
|
||||
_hasBegun = false;
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
size_t USBSerial::write(uint8 ch) {
|
||||
@ -112,23 +100,44 @@ size_t n = 0;
|
||||
|
||||
size_t USBSerial::write(const char *str) {
|
||||
size_t n = 0;
|
||||
this->write((const uint8*)str, strlen(str));
|
||||
this->write(str, strlen(str));
|
||||
return n;
|
||||
}
|
||||
|
||||
size_t USBSerial::write(const uint8 *buf, uint32 len)
|
||||
{
|
||||
size_t USBSerial::write(const void *buf, uint32 len) {
|
||||
size_t n = 0;
|
||||
if (!(bool) *this || !buf) {
|
||||
if (!this->isConnected() || !buf) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint32 txed = 0;
|
||||
while (txed < len) {
|
||||
txed += usb_cdcacm_tx((const uint8*)buf + txed, len - txed);
|
||||
uint32 old_txed = 0;
|
||||
uint32 start = millis();
|
||||
|
||||
uint32 sent = 0;
|
||||
|
||||
while (txed < len && (millis() - start < USB_TIMEOUT)) {
|
||||
sent = usb_cdcacm_tx((const uint8*)buf + txed, len - txed);
|
||||
txed += sent;
|
||||
if (old_txed != txed) {
|
||||
start = millis();
|
||||
}
|
||||
old_txed = txed;
|
||||
}
|
||||
|
||||
return n;
|
||||
|
||||
#if 0
|
||||
// this code leads to a serious performance drop and appears to be
|
||||
// unnecessary - everything seems to work fine without, -jcw, 2015-11-05
|
||||
// see http://stm32duino.com/posting.php?mode=quote&f=3&p=7746
|
||||
if (sent == USB_CDCACM_TX_EPSIZE) {
|
||||
while (usb_cdcacm_is_transmitting() != 0) {
|
||||
}
|
||||
/* flush out to avoid having the pc wait for more data */
|
||||
usb_cdcacm_tx(NULL, 0);
|
||||
}
|
||||
#endif
|
||||
return n;
|
||||
}
|
||||
|
||||
int USBSerial::available(void) {
|
||||
@ -159,25 +168,16 @@ void USBSerial::flush(void)
|
||||
return;
|
||||
}
|
||||
|
||||
uint32 USBSerial::read(uint8 * buf, uint32 len) {
|
||||
uint32 rxed = 0;
|
||||
while (rxed < len) {
|
||||
rxed += usb_cdcacm_rx(buf + rxed, len - rxed);
|
||||
uint32 USBSerial::read(void *buf, uint32 len) {
|
||||
if (!buf) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
return rxed;
|
||||
}
|
||||
uint32 rxed = 0;
|
||||
while (rxed < len) {
|
||||
rxed += usb_cdcacm_rx((uint8*)buf + rxed, len - rxed);
|
||||
}
|
||||
|
||||
size_t USBSerial::readBytes(char *buf, const size_t& len)
|
||||
{
|
||||
size_t rxed=0;
|
||||
unsigned long startMillis;
|
||||
startMillis = millis();
|
||||
if (len <= 0) return 0;
|
||||
do {
|
||||
rxed += usb_cdcacm_rx((uint8 *)buf + rxed, len - rxed);
|
||||
if (rxed == len) return rxed;
|
||||
} while(millis() - startMillis < _timeout);
|
||||
return rxed;
|
||||
}
|
||||
|
||||
@ -203,6 +203,10 @@ uint8 USBSerial::pending(void) {
|
||||
return usb_cdcacm_get_pending();
|
||||
}
|
||||
|
||||
uint8 USBSerial::isConnected(void) {
|
||||
return usb_is_connected(USBLIB) && usb_is_configured(USBLIB) && usb_cdcacm_get_dtr();
|
||||
}
|
||||
|
||||
uint8 USBSerial::getDTR(void) {
|
||||
return usb_cdcacm_get_dtr();
|
||||
}
|
||||
@ -211,10 +215,6 @@ uint8 USBSerial::getRTS(void) {
|
||||
return usb_cdcacm_get_rts();
|
||||
}
|
||||
|
||||
USBSerial::operator bool() {
|
||||
return usb_is_connected(USBLIB) && usb_is_configured(USBLIB) && usb_cdcacm_get_dtr();
|
||||
}
|
||||
|
||||
#if BOARD_HAVE_SERIALUSB
|
||||
#ifdef SERIAL_USB
|
||||
USBSerial Serial;
|
||||
|
@ -44,51 +44,38 @@ public:
|
||||
|
||||
void begin(void);
|
||||
|
||||
// Roger Clark. Added dummy function so that existing Arduino sketches which specify baud rate will compile.
|
||||
void begin(unsigned long);
|
||||
void begin(unsigned long, uint8_t);
|
||||
// Roger Clark. Added dummy function so that existing Arduino sketches which specify baud rate will compile.
|
||||
void begin(unsigned long);
|
||||
void begin(unsigned long, uint8_t);
|
||||
void end(void);
|
||||
|
||||
operator bool() { return true; } // Roger Clark. This is needed because in cardinfo.ino it does if (!Serial) . It seems to be a work around for the Leonardo that we needed to implement just to be compliant with the API
|
||||
|
||||
virtual int available(void);// Changed to virtual
|
||||
|
||||
size_t readBytes(char *buf, const size_t& len);
|
||||
uint32 read(uint8 * buf, uint32 len);
|
||||
// uint8 read(void);
|
||||
uint32 read(void *buf, uint32 len);
|
||||
// uint8 read(void);
|
||||
|
||||
// Roger Clark. added functions to support Arduino 1.0 API
|
||||
// Roger Clark. added functions to support Arduino 1.0 API
|
||||
virtual int peek(void);
|
||||
virtual int read(void);
|
||||
int availableForWrite(void);
|
||||
virtual void flush(void);
|
||||
|
||||
|
||||
|
||||
|
||||
size_t write(uint8);
|
||||
size_t write(const char *str);
|
||||
size_t write(const uint8*, uint32);
|
||||
size_t write(const void*, uint32);
|
||||
|
||||
uint8 getRTS();
|
||||
uint8 getDTR();
|
||||
uint8 isConnected();
|
||||
uint8 pending();
|
||||
|
||||
/* SukkoPera: This is the Arduino way to check if an USB CDC serial
|
||||
* connection is open.
|
||||
|
||||
* Used for instance in cardinfo.ino.
|
||||
*/
|
||||
operator bool();
|
||||
|
||||
/* Old libmaple way to check for serial connection.
|
||||
*
|
||||
* Deprecated, use the above.
|
||||
*/
|
||||
uint8 isConnected() __attribute__((deprecated("Use !Serial instead"))) { return (bool) *this; }
|
||||
|
||||
protected:
|
||||
static bool _hasBegun;
|
||||
};
|
||||
|
||||
#ifdef SERIAL_USB
|
||||
extern USBSerial Serial;
|
||||
#ifdef SERIAL_USB
|
||||
extern USBSerial Serial;
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
|
@ -76,7 +76,6 @@
|
||||
#include <stdint.h>
|
||||
|
||||
#include <WCharacter.h>
|
||||
#include <tone.h>
|
||||
|
||||
typedef unsigned int word;
|
||||
// typedef uint16 word;// definition from Arduino website, now appears to be incorrect for 32 bit devices
|
||||
@ -104,7 +103,5 @@ typedef unsigned int word;
|
||||
#define clockCyclesToMicroseconds(a) ( ((a) * 1000L) / (F_CPU / 1000L) )
|
||||
#define microsecondsToClockCycles(a) ( (a) * (F_CPU / 1000000L) )
|
||||
|
||||
#define digitalPinToInterrupt(pin) (pin)
|
||||
|
||||
#endif
|
||||
|
||||
|
@ -47,12 +47,3 @@ long random(long howsmall, long howbig) {
|
||||
return random(diff) + howsmall;
|
||||
}
|
||||
|
||||
extern uint16_t makeWord( uint16_t w )
|
||||
{
|
||||
return w ;
|
||||
}
|
||||
|
||||
extern uint16_t makeWord( uint8_t h, uint8_t l )
|
||||
{
|
||||
return (h << 8) | l ;
|
||||
}
|
||||
|
@ -33,7 +33,6 @@
|
||||
#define _WIRISH_WIRISH_MATH_H_
|
||||
|
||||
#include <math.h>
|
||||
#include <stdint.h>
|
||||
|
||||
/**
|
||||
* @brief Initialize the pseudo-random number generator.
|
||||
@ -79,12 +78,11 @@ long random(long min, long max);
|
||||
* @param toEnd the end of the value's mapped range.
|
||||
* @return the mapped value.
|
||||
*/
|
||||
// Fix by Pito 9/2017
|
||||
static inline int32_t map(int32_t value, int32_t fromStart, int32_t fromEnd,
|
||||
int32_t toStart, int32_t toEnd) {
|
||||
return ((int64_t)(value - fromStart) * (toEnd - toStart)) / (fromEnd - fromStart) +
|
||||
toStart;
|
||||
}
|
||||
static inline long map(long value, long fromStart, long fromEnd,
|
||||
long toStart, long toEnd) {
|
||||
return (value - fromStart) * (toEnd - toStart) / (fromEnd - fromStart) +
|
||||
toStart;
|
||||
}
|
||||
|
||||
#define PI 3.1415926535897932384626433832795
|
||||
#define HALF_PI 1.5707963267948966192313216916398
|
||||
@ -163,9 +161,4 @@ double sqrt(double x);
|
||||
*/
|
||||
double pow(double x, double y);
|
||||
|
||||
extern uint16_t makeWord( uint16_t w ) ;
|
||||
extern uint16_t makeWord( uint8_t h, uint8_t l ) ;
|
||||
|
||||
#define word(...) makeWord(__VA_ARGS__)
|
||||
|
||||
#endif
|
||||
|
@ -35,28 +35,3 @@ void shiftOut(uint8 dataPin, uint8 clockPin, uint8 bitOrder, uint8 value) {
|
||||
gpio_toggle_bit(PIN_MAP[clockPin].gpio_device, PIN_MAP[clockPin].gpio_bit);// togglePin(clockPin);
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t shiftIn( uint32_t ulDataPin, uint32_t ulClockPin, uint32_t ulBitOrder )
|
||||
{
|
||||
uint8_t value = 0 ;
|
||||
uint8_t i ;
|
||||
|
||||
|
||||
for ( i=0 ; i < 8 ; ++i )
|
||||
{
|
||||
digitalWrite( ulClockPin, HIGH ) ;
|
||||
|
||||
if ( ulBitOrder == LSBFIRST )
|
||||
{
|
||||
value |= digitalRead( ulDataPin ) << i ;
|
||||
}
|
||||
else
|
||||
{
|
||||
value |= digitalRead( ulDataPin ) << (7 - i) ;
|
||||
}
|
||||
|
||||
digitalWrite( ulClockPin, LOW ) ;
|
||||
}
|
||||
|
||||
return value ;
|
||||
}
|
||||
|
@ -32,15 +32,11 @@
|
||||
|
||||
#include <libmaple/libmaple_types.h>
|
||||
#include <libmaple/delay.h>
|
||||
#include "Arduino.h"
|
||||
|
||||
void delay(unsigned long ms) {
|
||||
uint32 start = millis();
|
||||
do
|
||||
{
|
||||
yield();
|
||||
}
|
||||
while (millis() - start < ms);
|
||||
while (millis() - start < ms)
|
||||
;
|
||||
}
|
||||
|
||||
void delayMicroseconds(uint32 us) {
|
||||
|
@ -521,28 +521,6 @@ uint16 EEPROMClass::write(uint16 Address, uint16 Data)
|
||||
return status;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Writes/upadtes variable data in EEPROM.
|
||||
The value is written only if differs from the one already saved at the same address.
|
||||
* @param VirtAddress: Variable virtual address
|
||||
* @param Data: 16 bit data to be written
|
||||
* @retval Success or error status:
|
||||
* - EEPROM_SAME_VALUE: If new Data matches existing EEPROM Data
|
||||
* - FLASH_COMPLETE: on success
|
||||
* - EEPROM_BAD_ADDRESS: if address = 0xFFFF
|
||||
* - EEPROM_PAGE_FULL: if valid page is full
|
||||
* - EEPROM_NO_VALID_PAGE: if no valid page was found
|
||||
* - EEPROM_OUT_SIZE: if no empty EEPROM variables
|
||||
* - Flash error code: on write Flash error
|
||||
*/
|
||||
uint16 EEPROMClass::update(uint16 Address, uint16 Data)
|
||||
{
|
||||
if (read(Address) == Data)
|
||||
return EEPROM_SAME_VALUE;
|
||||
else
|
||||
return write(Address, Data);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Return number of variable
|
||||
* @retval Number of variables
|
||||
|
@ -47,7 +47,6 @@ enum : uint16
|
||||
EEPROM_BAD_ADDRESS = ((uint16)0x0082),
|
||||
EEPROM_BAD_FLASH = ((uint16)0x0083),
|
||||
EEPROM_NOT_INIT = ((uint16)0x0084),
|
||||
EEPROM_SAME_VALUE = ((uint16)0x0085),
|
||||
EEPROM_NO_VALID_PAGE = ((uint16)0x00AB)
|
||||
};
|
||||
|
||||
@ -68,7 +67,6 @@ public:
|
||||
uint16 read (uint16 address);
|
||||
uint16 read (uint16 address, uint16 *data);
|
||||
uint16 write(uint16 address, uint16 data);
|
||||
uint16 update(uint16 address, uint16 data);
|
||||
uint16 count(uint16 *);
|
||||
uint16 maxcount(void);
|
||||
|
||||
|
@ -31,6 +31,7 @@
|
||||
|
||||
#include "SPI.h"
|
||||
|
||||
//#define SPI_DEBUG
|
||||
|
||||
#include <libmaple/timer.h>
|
||||
#include <libmaple/util.h>
|
||||
@ -40,8 +41,6 @@
|
||||
#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 */
|
||||
@ -91,80 +90,79 @@ static const spi_pins board_spi_pins[] __FLASH__ = {
|
||||
* 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
|
||||
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;
|
||||
|
||||
// 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;
|
||||
_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
|
||||
|
||||
//pinMode(BOARD_SPI_DEFAULT_SS,OUTPUT);
|
||||
}
|
||||
|
||||
/*
|
||||
* 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);
|
||||
uint32 flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize | SPI_SW_SLAVE | SPI_SOFT_SS);
|
||||
#ifdef SPI_DEBUG
|
||||
Serial.print("spi_master_enable("); Serial.print(_currentSetting->clockDivider); Serial.print(","); Serial.print(_currentSetting->dataMode); Serial.print(","); Serial.print(flags); Serial.println(")");
|
||||
#endif
|
||||
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);
|
||||
uint32 flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize | SPI_SW_SLAVE);
|
||||
#ifdef SPI_DEBUG
|
||||
Serial.print("spi_slave_enable("); Serial.print(_currentSetting->dataMode); Serial.print(","); Serial.print(flags); Serial.println(")");
|
||||
#endif
|
||||
spi_slave_enable(_currentSetting->spi_d, (spi_mode)_currentSetting->dataMode, flags);
|
||||
// added for DMA callbacks.
|
||||
_currentSetting->state = SPI_STATE_READY;
|
||||
}
|
||||
|
||||
void SPIClass::end(void) {
|
||||
@ -183,25 +181,28 @@ void SPIClass::end(void) {
|
||||
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);
|
||||
#ifdef SPI_DEBUG
|
||||
Serial.print("Clock divider set to "); Serial.println(clockDivider);
|
||||
#endif
|
||||
_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;
|
||||
#ifdef SPI_DEBUG
|
||||
Serial.print("Bit order set to "); Serial.println(bitOrder);
|
||||
#endif
|
||||
_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.
|
||||
@ -210,11 +211,9 @@ void SPIClass::setBitOrder(BitOrder bitOrder)
|
||||
*/
|
||||
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;
|
||||
_currentSetting->dataSize = datasize;
|
||||
uint32 cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_DFF);
|
||||
_currentSetting->spi_d->regs->CR1 = cr1 | (datasize & SPI_CR1_DFF);
|
||||
}
|
||||
|
||||
void SPIClass::setDataMode(uint8_t dataMode)
|
||||
@ -244,44 +243,59 @@ bit 0 - CPHA : Clock phase
|
||||
|
||||
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));
|
||||
#ifdef SPI_DEBUG
|
||||
Serial.print("Data mode set to "); Serial.println(dataMode);
|
||||
#endif
|
||||
_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();
|
||||
#ifdef SPI_DEBUG
|
||||
Serial.println("SPIClass::beginTransaction");
|
||||
#endif
|
||||
//_SSPin=pin;
|
||||
//pinMode(_SSPin,OUTPUT);
|
||||
//digitalWrite(_SSPin,LOW);
|
||||
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();
|
||||
#ifdef SPI_DEBUG
|
||||
Serial.println(F("SPIClass::beginTransactionSlave"));
|
||||
#endif
|
||||
setBitOrder(settings.bitOrder);
|
||||
setDataMode(settings.dataMode);
|
||||
setDataSize(settings.dataSize);
|
||||
beginSlave();
|
||||
}
|
||||
|
||||
void SPIClass::endTransaction(void)
|
||||
{
|
||||
//digitalWrite(_SSPin,HIGH);
|
||||
#ifdef SPI_DEBUG
|
||||
Serial.println("SPIClass::endTransaction");
|
||||
#endif
|
||||
//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();
|
||||
}
|
||||
}
|
||||
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
|
||||
}
|
||||
|
||||
@ -290,354 +304,211 @@ void SPIClass::endTransaction(void)
|
||||
* I/O
|
||||
*/
|
||||
|
||||
uint16 SPIClass::read(void)
|
||||
{
|
||||
while ( spi_is_rx_nonempty(_currentSetting->spi_d)==0 ) ;
|
||||
return (uint16)spi_rx_reg(_currentSetting->spi_d);
|
||||
uint8 SPIClass::read(void) {
|
||||
uint8 buf[1];
|
||||
this->read(buf, 1);
|
||||
return buf[0];
|
||||
}
|
||||
|
||||
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
|
||||
void SPIClass::read(uint8 *buf, uint32 len) {
|
||||
uint32 rxed = 0;
|
||||
while (rxed < len) {
|
||||
while (!spi_is_rx_nonempty(_currentSetting->spi_d))
|
||||
;
|
||||
buf[rxed++] = (uint8)spi_rx_reg(_currentSetting->spi_d);
|
||||
}
|
||||
// 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::write(uint16 data) {
|
||||
// this->write(&data, 1);
|
||||
|
||||
/* 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)
|
||||
* The original method, of calling write(*data, length) .
|
||||
* This almost doubles the speed of this function.
|
||||
*/
|
||||
|
||||
spi_tx_reg(_currentSetting->spi_d, data); // "2. Write the first data item 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(uint8 byte) {
|
||||
// this->write(&byte, 1);
|
||||
|
||||
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
|
||||
/* 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)
|
||||
* The original method, of calling write(*data, length) .
|
||||
* This almost doubles the speed of this function.
|
||||
*/
|
||||
|
||||
// spi_tx_reg(_currentSetting->spi_d, byte); // "2. Write the first data item 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::write(const uint8 *data, uint32 length) {
|
||||
uint32 txed = 0;
|
||||
while (txed < length) {
|
||||
txed += spi_tx(_currentSetting->spi_d, data + txed, length - txed);
|
||||
}
|
||||
while ( (regs->SR & SPI_SR_BSY) != 0); // wait until BSY=0 before returning
|
||||
while (spi_is_tx_empty(_currentSetting->spi_d) == 0); // "4. After writing the last data item into the SPI_DR register, wait until TXE=1 ..."
|
||||
while (spi_is_busy(_currentSetting->spi_d) != 0); // "... then wait until BSY=0, this indicates that the transmission of the last data is complete."
|
||||
// taken from SdSpiSTM32F1.cpp - Victor's lib, and adapted to support device selection
|
||||
if (spi_is_rx_nonempty(_currentSetting->spi_d)) {
|
||||
uint8_t b = spi_rx_reg(_currentSetting->spi_d);
|
||||
}
|
||||
}
|
||||
|
||||
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."
|
||||
uint16_t SPIClass::transfer16(uint16_t wr_data) const {
|
||||
spi_tx_reg(_currentSetting->spi_d, wr_data); // "2. Write the first data item to be transmitted into the SPI_DR register (this clears the TXE flag)."
|
||||
while (spi_is_rx_nonempty(_currentSetting->spi_d) == 0); // "4. Wait until RXNE=1 ..."
|
||||
uint16_t rd_data = spi_rx_reg(_currentSetting->spi_d); // "... and read the last received data."
|
||||
// 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."
|
||||
return rd_data;
|
||||
}
|
||||
|
||||
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."
|
||||
uint8 SPIClass::transfer(uint8 byte) const {
|
||||
spi_tx_reg(_currentSetting->spi_d, byte); // "2. Write the first data item to be transmitted into the SPI_DR register (this clears the TXE flag)."
|
||||
while (spi_is_rx_nonempty(_currentSetting->spi_d) == 0); // "4. Wait until RXNE=1 ..."
|
||||
uint8 b = spi_rx_reg(_currentSetting->spi_d); // "... and read the last received data."
|
||||
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."
|
||||
return b;
|
||||
}
|
||||
|
||||
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) {
|
||||
uint8 SPIClass::dmaTransfer(uint8 *transmitBuf, uint8 *receiveBuf, uint16 length) {
|
||||
if (length == 0) return 0;
|
||||
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);
|
||||
//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);
|
||||
}
|
||||
// dma_attach_interrupt(DMA1, DMA_CH3, &SPIClass::DMA1_CH3_Event);
|
||||
|
||||
// RX
|
||||
spi_rx_dma_enable(_currentSetting->spi_d);
|
||||
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &_currentSetting->spi_d->regs->DR, DMA_SIZE_8BITS,
|
||||
receiveBuf, DMA_SIZE_8BITS, (DMA_MINC_MODE | DMA_TRNS_CMPLT));// receive buffer DMA
|
||||
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, length);
|
||||
|
||||
// TX
|
||||
spi_tx_dma_enable(_currentSetting->spi_d);
|
||||
if (!transmitBuf) {
|
||||
static uint8_t ff = 0XFF;
|
||||
transmitBuf = &ff;
|
||||
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, DMA_SIZE_8BITS,
|
||||
transmitBuf, DMA_SIZE_8BITS, (DMA_FROM_MEM | DMA_TRNS_CMPLT));// Transmit FF repeatedly
|
||||
}
|
||||
else {
|
||||
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, DMA_SIZE_8BITS,
|
||||
transmitBuf, DMA_SIZE_8BITS, (DMA_MINC_MODE | DMA_FROM_MEM | DMA_TRNS_CMPLT));// Transmit buffer DMA
|
||||
}
|
||||
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
|
||||
|
||||
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;
|
||||
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);// enable receive
|
||||
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);// enable transmit
|
||||
|
||||
// while (dma1_ch3_Active);
|
||||
// if (receiveBuf) {
|
||||
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 ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & 0x2)==0) {//Avoid interrupts and just loop waiting for the flag to be set.
|
||||
if ((millis() - m) > 100) {
|
||||
// dma1_ch3_Active = 0;
|
||||
b = 2;
|
||||
break;
|
||||
}
|
||||
}
|
||||
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
|
||||
|
||||
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);
|
||||
// }
|
||||
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."
|
||||
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;
|
||||
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel);
|
||||
spi_rx_dma_disable(_currentSetting->spi_d); // And disable generation of DMA request from the SPI port so other peripherals can use the channels
|
||||
spi_tx_dma_disable(_currentSetting->spi_d);
|
||||
if (spi_is_rx_nonempty(_currentSetting->spi_d) != 0){; // "4. Wait until RXNE=1 ..."
|
||||
uint8 x = spi_rx_reg(_currentSetting->spi_d); // "... and read the last received data."
|
||||
}
|
||||
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);
|
||||
|
||||
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 = 0;
|
||||
// dma1_ch3_Active=true;
|
||||
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);
|
||||
// dma_attach_interrupt(DMA1, DMA_CH3, &SPIClass::DMA1_CH3_Event);
|
||||
|
||||
_currentSetting->state = SPI_STATE_TRANSMIT;
|
||||
// TX
|
||||
spi_tx_dma_enable(_currentSetting->spi_d);
|
||||
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, DMA_SIZE_8BITS,
|
||||
transmitBuf, DMA_SIZE_8BITS, flags);// Transmit buffer DMA
|
||||
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
|
||||
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);// enable transmit
|
||||
|
||||
// while (dma1_ch3_Active);
|
||||
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & 0x2)==0); //Avoid interrupts and just loop waiting for the flag to be set.
|
||||
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
|
||||
|
||||
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."
|
||||
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
|
||||
spi_tx_dma_disable(_currentSetting->spi_d);
|
||||
if (spi_is_rx_nonempty(_currentSetting->spi_d) != 0){; // "4. Wait until RXNE=1 ..."
|
||||
uint8 x = spi_rx_reg(_currentSetting->spi_d); // "... and read the last received data."
|
||||
}
|
||||
return b;
|
||||
}
|
||||
|
||||
uint8 SPIClass::dmaSend(uint16 *transmitBuf, uint16 length, bool minc) {
|
||||
if (length == 0) return 0;
|
||||
uint32 flags = ((DMA_MINC_MODE * minc) | DMA_FROM_MEM | DMA_TRNS_CMPLT);
|
||||
uint8 b;
|
||||
dma1_ch3_Active=true;
|
||||
dma_init(_currentSetting->spiDmaDev);
|
||||
// dma_attach_interrupt(DMA1, DMA_CH3, &SPIClass::DMA1_CH3_Event);
|
||||
|
||||
/*
|
||||
New functions added to manage callbacks.
|
||||
Victor Perez 2017
|
||||
*/
|
||||
// TX
|
||||
spi_tx_dma_enable(_currentSetting->spi_d);
|
||||
dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, DMA_SIZE_16BITS,
|
||||
transmitBuf, DMA_SIZE_16BITS, flags);// Transmit buffer DMA
|
||||
dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length);
|
||||
dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);// enable transmit
|
||||
|
||||
// while (dma1_ch3_Active);
|
||||
while ((dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & 0x2)==0); //Avoid interrupts and just loop waiting for the flag to be set.
|
||||
dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
|
||||
|
||||
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);
|
||||
}
|
||||
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."
|
||||
dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel);
|
||||
spi_tx_dma_disable(_currentSetting->spi_d);
|
||||
if (spi_is_rx_nonempty(_currentSetting->spi_d) != 0){; // "4. Wait until RXNE=1 ..."
|
||||
b = spi_rx_reg(_currentSetting->spi_d); // "... and read the last received data."
|
||||
}
|
||||
return b;
|
||||
}
|
||||
|
||||
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()
|
||||
// Should be enableInterrupt()
|
||||
}
|
||||
|
||||
void SPIClass::detachInterrupt(void) {
|
||||
// Should be disableInterrupt()
|
||||
// Should be disableInterrupt()
|
||||
}
|
||||
|
||||
/*
|
||||
@ -665,39 +536,28 @@ uint8 SPIClass::nssPin(void) {
|
||||
*/
|
||||
|
||||
uint8 SPIClass::send(uint8 data) {
|
||||
this->write(data);
|
||||
return 1;
|
||||
uint8 buf[] = {data};
|
||||
return this->send(buf, 1);
|
||||
}
|
||||
|
||||
uint8 SPIClass::send(uint8 *buf, uint32 len) {
|
||||
this->write(buf, len);
|
||||
return len;
|
||||
uint32 txed = 0;
|
||||
uint8 ret = 0;
|
||||
while (txed < len) {
|
||||
this->write(buf[txed++]);
|
||||
ret = this->read();
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
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
|
||||
*/
|
||||
* Auxiliary functions
|
||||
*/
|
||||
|
||||
static const spi_pins* dev_to_spi_pins(spi_dev *dev) {
|
||||
switch (dev->clk_id) {
|
||||
@ -738,8 +598,8 @@ static void configure_gpios(spi_dev *dev, bool as_master) {
|
||||
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);
|
||||
scki->gpio_device, scki->gpio_bit, misoi->gpio_bit,
|
||||
mosii->gpio_bit);
|
||||
}
|
||||
|
||||
static const spi_baud_rate baud_rates[8] __FLASH__ = {
|
||||
@ -754,23 +614,26 @@ static const spi_baud_rate baud_rates[8] __FLASH__ = {
|
||||
};
|
||||
|
||||
/*
|
||||
* Note: This assumes you're on a LeafLabs-style board
|
||||
* (CYCLES_PER_MICROSECOND == 72, APB2 at 72MHz, APB1 at 36MHz).
|
||||
*/
|
||||
* 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;
|
||||
uint32_t clock = 0, i;
|
||||
#ifdef SPI_DEBUG
|
||||
Serial.print("determine_baud_rate("); Serial.print(freq); Serial.println(")");
|
||||
#endif
|
||||
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
|
||||
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++;
|
||||
clock /= 2;
|
||||
i++;
|
||||
}
|
||||
return baud_rates[i];
|
||||
return baud_rates[i];
|
||||
}
|
||||
|
||||
SPIClass SPI(1);
|
||||
|
@ -99,13 +99,6 @@
|
||||
#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) {
|
||||
@ -122,13 +115,6 @@ public:
|
||||
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) {
|
||||
@ -141,31 +127,21 @@ private:
|
||||
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;
|
||||
uint32_t dataSize;
|
||||
|
||||
spi_dev *spi_d;
|
||||
uint8_t _SSPin;
|
||||
uint32_t clockDivider;
|
||||
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
|
||||
volatile static bool dma1_ch3_Active;
|
||||
|
||||
/**
|
||||
* @brief Wirish SPI interface.
|
||||
@ -176,6 +152,8 @@ static void (*_spi3_this);
|
||||
class SPIClass {
|
||||
public:
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @param spiPortNumber Number of the SPI port to manage.
|
||||
*/
|
||||
@ -185,6 +163,8 @@ public:
|
||||
* Set up/tear down
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief Equivalent to begin(SPI_1_125MHZ, MSBFIRST, 0).
|
||||
*/
|
||||
@ -230,55 +210,46 @@ public:
|
||||
*/
|
||||
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.
|
||||
* @brief Return the next unread byte.
|
||||
*
|
||||
* If there is no unread byte/word waiting, this function will block
|
||||
* If there is no unread byte waiting, this function will block
|
||||
* until one is received.
|
||||
*/
|
||||
uint16 read(void);
|
||||
uint8 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
|
||||
* @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.
|
||||
* @brief Transmit a byte.
|
||||
* @param data Byte to transmit.
|
||||
*/
|
||||
void write(uint16 data);
|
||||
void write16(uint16 data); // write 2 bytes in 8 bit mode (DFF=0)
|
||||
// void write(uint8 data);
|
||||
|
||||
/**
|
||||
* @brief Transmit one byte/word a specified number of times.
|
||||
* @brief Transmit a half word.
|
||||
* @param data to transmit.
|
||||
*/
|
||||
void write(uint16 data, uint32 n);
|
||||
|
||||
void write(uint16 data);
|
||||
|
||||
/**
|
||||
* @brief Transmit multiple bytes/words.
|
||||
* @param buffer Bytes/words to transmit.
|
||||
* @param length Number of bytes/words in buffer to transmit.
|
||||
* @brief Transmit multiple bytes.
|
||||
* @param buffer Bytes to transmit.
|
||||
* @param length Number of bytes in buffer to transmit.
|
||||
*/
|
||||
void write(const void * buffer, uint32 length);
|
||||
void write(const uint8 *buffer, uint32 length);
|
||||
|
||||
/**
|
||||
* @brief Transmit a byte, then return the next unread byte.
|
||||
@ -290,10 +261,9 @@ public:
|
||||
*/
|
||||
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.
|
||||
*
|
||||
@ -301,25 +271,31 @@ public:
|
||||
* @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);
|
||||
uint8 dmaTransfer(uint8 *transmitBuf, uint8 *receiveBuf, 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.
|
||||
* @brief Sets up a DMA Transmit for bytes.
|
||||
*
|
||||
* This function only transmits and does not care about the RX fifo.
|
||||
* This function transmits and does not care about the RX fifo.
|
||||
*
|
||||
* @param data buffer half words to transmit,
|
||||
* @param transmitBuf buffer Bytes 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 dmaSend(uint8 *transmitBuf, uint16 length, bool minc = 1);
|
||||
|
||||
/**
|
||||
* @brief Sets up a DMA Transmit for half words.
|
||||
* SPI PERFIPHERAL MUST BE SET TO 16 BIT MODE BEFORE
|
||||
*
|
||||
* This function 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 (default if blank), clear to use Circular mode.
|
||||
*/
|
||||
uint8 dmaSend(uint16 *transmitBuf, uint16 length, bool minc = 1);
|
||||
|
||||
uint8 dmaSendAsync(const void * transmitBuf, uint16 length, bool minc = 1);
|
||||
/*
|
||||
* Pin accessors
|
||||
*/
|
||||
@ -351,20 +327,23 @@ public:
|
||||
* 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
|
||||
}
|
||||
|
||||
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 --------------------------- */
|
||||
|
||||
@ -397,25 +376,21 @@ public:
|
||||
* @see HardwareSPI::read()
|
||||
*/
|
||||
uint8 recv(void);
|
||||
|
||||
|
||||
private:
|
||||
|
||||
/*
|
||||
static inline void DMA1_CH3_Event() {
|
||||
dma1_ch3_Active = 0;
|
||||
// dma_disable(DMA1, DMA_CH3);
|
||||
// dma_disable(DMA1, DMA_CH2);
|
||||
|
||||
// To Do. Need to wait for
|
||||
}
|
||||
*/
|
||||
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;
|
||||
|
@ -52,9 +52,9 @@ extern "C"{
|
||||
* One byte is left free to distinguish empty from full. */
|
||||
typedef struct ring_buffer {
|
||||
volatile uint8 *buf; /**< Buffer items are stored into */
|
||||
volatile uint16 head; /**< Index of the next item to remove */
|
||||
volatile uint16 tail; /**< Index where the next item will get inserted */
|
||||
volatile uint16 size; /**< Buffer capacity minus one */
|
||||
uint16 head; /**< Index of the next item to remove */
|
||||
uint16 tail; /**< Index where the next item will get inserted */
|
||||
uint16 size; /**< Buffer capacity minus one */
|
||||
} ring_buffer;
|
||||
|
||||
/**
|
||||
|
@ -1,270 +0,0 @@
|
||||
/******************************************************************************
|
||||
*
|
||||
* 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 sdio.h
|
||||
* @brief Secure digital input/output interface.
|
||||
*/
|
||||
|
||||
#ifndef _SDIO_H_
|
||||
#define _SDIO_H_
|
||||
|
||||
#include <libmaple/libmaple_types.h>
|
||||
#include <libmaple/stm32.h>
|
||||
#include <libmaple/gpio.h>
|
||||
|
||||
|
||||
/*
|
||||
#include <libmaple/rcc.h>
|
||||
#include <libmaple/nvic.h>
|
||||
|
||||
//#include <boards.h>
|
||||
#include <stdint.h>
|
||||
//#include <wirish.h>
|
||||
*/
|
||||
|
||||
#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY)
|
||||
|
||||
/*
|
||||
* DMA controller and channel used in STM32F103
|
||||
*/
|
||||
|
||||
#define SDIO_DMA_DEV DMA2
|
||||
#define SDIO_DMA_CHANNEL DMA_CH4
|
||||
/*
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
*/
|
||||
|
||||
/*
|
||||
* Register maps and devices
|
||||
*/
|
||||
|
||||
// SDIO register map type
|
||||
typedef struct sdio_reg_map {
|
||||
__io uint32 POWER; // 0x00
|
||||
__io uint32 CLKCR; // 0x04
|
||||
__io uint32 ARG; // 0x08
|
||||
__io uint32 CMD; // 0x0C
|
||||
__io uint32 RESPCMD; // 0x10 (0x3F)
|
||||
const uint32 RESP[4]; // 0x14 - contain the card status, which is part of the received response.
|
||||
__io uint32 DTIMER; // 0x24 - contains the data timeout period, in card bus clock periods.
|
||||
__io uint32 DLEN; // 0x28 (0x01FF FFFF) - contains the number of data bytes to be transferred
|
||||
__io uint32 DCTRL; // 0x2C
|
||||
__io uint32 DCOUNT; // 0x30 (0x01FF FFFF)
|
||||
__io uint32 STA; // 0x34
|
||||
__io uint32 ICR; // 0x38
|
||||
__io uint32 MASK; // 0x3C
|
||||
const uint32 RESERVED1[2];
|
||||
__io uint32 FIFOCNT; // 0x48 (0x01FF FFFF)
|
||||
const uint32 RESERVED2[13];
|
||||
__io uint32 FIFO; // 0x80
|
||||
} sdio_reg_map;
|
||||
#define sdio_dev sdio_reg_map
|
||||
|
||||
/** SDIO register map base pointer */
|
||||
#define SDIO_BASE ((struct sdio_reg_map*)0x40018000)
|
||||
|
||||
extern sdio_dev * SDIO;
|
||||
|
||||
/*
|
||||
* Register bit definitions
|
||||
*/
|
||||
|
||||
/* NOR/PSRAM chip-select control registers */
|
||||
|
||||
// SDIO_POWER register bits
|
||||
// At least seven HCLK clock periods are needed between two write accesses to this register.
|
||||
// After a data write, data cannot be written to this register for three SDIOCLK clock periods
|
||||
// plus two PCLK2 clock periods.
|
||||
#define SDIO_POWER_PWRCTRL_OFF 0x00
|
||||
#define SDIO_POWER_PWRCTRL_ON 0x03
|
||||
|
||||
// SDIO_CLKCR register bits
|
||||
// Controls the SDIO_CK output clock.
|
||||
// After a data write, data cannot be written to this register for three SDIOCLK clock periods
|
||||
// plus two PCLK2 clock periods. SDIO_CK can also be stopped during the read wait interval
|
||||
// for SD I/O cards: in this case the SDIO_CLKCR register does not control SDIO_CK.
|
||||
#define SDIO_CLKCR_HWFC_EN (1<<14) // HW Flow Control enable - DON'T USE!!! (see errata sheet 2.12.1)
|
||||
// Overrun errors (Rx mode) and FIFO underrun (Tx mode)
|
||||
// should be managed by the application software.
|
||||
#define SDIO_CLKCR_NEGEDGE (1<<13) // SDIO_CK de-phasing selection bit - DON'T USE!!! (see errata sheet 2.12.4)
|
||||
#define SDIO_CLKCR_WIDBUS (3<<11) // Data bus width
|
||||
#define SDIO_CLKCR_WIDBUS_1BIT (0<<11) // 1 bit (SDIO_D0 used)
|
||||
#define SDIO_CLKCR_WIDBUS_4BIT (1<<11) // 4-bit (SDIO_D[3:0] used)
|
||||
#define SDIO_CLKCR_BYPASS (1<<10) // Clock divider bypass enable bit - SDIO_CK = SDIOCLK, CLKDIV not relevant.
|
||||
#define SDIO_CLKCR_PWRSAV (1<<9) // 0: SDIO_CK clock is always enabled, 1: SDIO_CK is only enabled when the bus is active
|
||||
#define SDIO_CLKCR_CLKEN (1<<8) // Clock enable
|
||||
#define SDIO_CLKCR_CLKDIV (0xFF) // SDIO_CK = SDIOCLK / [CLKDIV + 2]
|
||||
#define SDIOCLK 72000000UL // SDIO master clock frequency
|
||||
|
||||
// SDIO_CMD register bits
|
||||
// After a data write, data cannot be written to this register for three SDIOCLK clock periods
|
||||
// plus two PCLK2 clock periods.
|
||||
// MultiMediaCards can send two kinds of response: short responses, 48 bits long, or long
|
||||
// responses,136 bits long. SD card and SD I/O card can send only short responses, the
|
||||
// argument can vary according to the type of response: the software will distinguish the type
|
||||
// of response according to the sent command. CE-ATA devices send only short responses.
|
||||
#define SDIO_CMD_ATACMD (1<<14)
|
||||
#define SDIO_CMD_NIEN (1<<13)
|
||||
#define SDIO_CMD_ENCMDCOMPL (1<<12)
|
||||
#define SDIO_CMD_SDIOSUSPEND (1<<11)
|
||||
#define SDIO_CMD_CPSMEN (1<<10)
|
||||
#define SDIO_CMD_WAITPEND (1<<9)
|
||||
#define SDIO_CMD_WAITINT (1<<8)
|
||||
#define SDIO_CMD_WAITRESP (3<<6)
|
||||
#define SDIO_CMD_WAIT_NO_RESP (0<<6)
|
||||
#define SDIO_CMD_WAIT_SHORT_RESP (1<<6)
|
||||
#define SDIO_CMD_WAIT_LONG_RESP (3<<6)
|
||||
#define SDIO_CMD_CMDINDEX (0x3F)
|
||||
|
||||
// SDIO_DLEN register bits
|
||||
// For a block data transfer, the value in the data length register must be a multiple of the block
|
||||
// size (see SDIO_DCTRL). A data transfer must be written to the data timer register and the
|
||||
// data length register before being written to the data control register.
|
||||
// For an SDIO multibyte transfer the value in the data length register must be between 1 and 512.
|
||||
#define SDIO_DLEN_DATALENGTH (0x01FFFFFF)
|
||||
|
||||
// SDIO_DCTRL register bits
|
||||
// Controls the data path state machine (DPSM).
|
||||
// After a data write, data cannot be written to this register for three SDIOCLK clock periods
|
||||
// plus two PCLK2 clock periods.
|
||||
#define SDIO_DCTRL_SDIOEN (1<<11) // the DPSM performs an SD I/O-card-specific operation.
|
||||
#define SDIO_DCTRL_RWMODE (1<<10) // 0: Read Wait control stopping SDIO_D2, 1:Read Wait control using SDIO_CK
|
||||
#define SDIO_DCTRL_RWSTOP (1<<9) // 0: Read wait in progress if RWSTART bit is set, 1: Enable for read wait stop if RWSTART bit is set
|
||||
#define SDIO_DCTRL_RWSTART (1<<8) // read wait operation starts
|
||||
#define SDIO_DCTRL_DBLOCKSIZE (0xF<<4) // Define the data block length when the block data transfer mode is selected: 2^N bytes
|
||||
#define SDIO_BLOCKSIZE_64 (6<<4)
|
||||
#define SDIO_BLOCKSIZE_512 (9<<4)
|
||||
#define SDIO_DCTRL_DMAEN (1<<3) // DMA enable
|
||||
#define SDIO_DCTRL_DTMODE (1<<2) // Data transfer mode selection: 0: Block data transfer, 1: Stream or SDIO multi-byte data transfer
|
||||
#define SDIO_DCTRL_DTDIR (1<<1) // Data transfer direction selection: 0: From controller to card, 1: From card to controller.
|
||||
#define SDIO_DIR_TX (0<<1)
|
||||
#define SDIO_DIR_RX (1<<1)
|
||||
#define SDIO_DCTRL_DTEN (1<<0) // Start data transfer. Depending on the direction bit, DTDIR,
|
||||
// the DPSM moves to the Wait_S, Wait_R state or Readwait if RW Start is set immediately at
|
||||
// the beginning of the transfer. It is not necessary to clear the enable bit after the end of a data
|
||||
// transfer but the SDIO_DCTRL must be updated to enable a new data transfer
|
||||
// The meaning of the DTMODE bit changes according to the value of the SDIOEN bit:
|
||||
// When DTEN=0 and DTMODE=1, the MultiMediaCard stream mode is enabled.
|
||||
// When DTEN=1 and DTMODE=1, the peripheral enables an SDIO multi-byte transfer.
|
||||
|
||||
// SDIO_STA register bits
|
||||
#define SDIO_STA_CEATAEND (1<<23) // CE-ATA command completion signal received for CMD61
|
||||
#define SDIO_STA_SDIOIT (1<<22) // SDIO interrupt received
|
||||
#define SDIO_STA_RXDAVL (1<<21) // Data available in receive FIFO
|
||||
#define SDIO_STA_TXDAVL (1<<20) // Data available in transmit FIFO
|
||||
#define SDIO_STA_RXFIFOE (1<<19) // Receive FIFO empty
|
||||
#define SDIO_STA_TXFIFOE (1<<18) // Transmit FIFO empty (2 words)
|
||||
#define SDIO_STA_RXFIFOF (1<<17) // Receive FIFO full (2 words before the FIFO is full.)
|
||||
#define SDIO_STA_TXFIFOF (1<<16) // Transmit FIFO full
|
||||
#define SDIO_STA_RXFIFOHF (1<<15) // Receive FIFO half full: there are at least 8 words in the FIFO
|
||||
#define SDIO_STA_TXFIFOHE (1<<14) // Transmit FIFO half empty: at least 8 words can be written into the FIFO
|
||||
#define SDIO_STA_RXACT (1<<13) // Data receive in progress
|
||||
#define SDIO_STA_TXACT (1<<12) // Data transmit in progress
|
||||
#define SDIO_STA_CMDACT (1<<11) // Command transfer in progress
|
||||
#define SDIO_STA_DBCKEND (1<<10) // Data block sent/received (CRC check passed)
|
||||
#define SDIO_STA_STBITERR (1<<9) // Start bit not detected on all data signals in wide bus mode
|
||||
#define SDIO_STA_DATAEND (1<<8) // Data end (data counter SDIOCOUNT is zero)
|
||||
#define SDIO_STA_CMDSENT (1<<7) // Command sent (no response required)
|
||||
#define SDIO_STA_CMDREND (1<<6) // Command response received (CRC check passed)
|
||||
#define SDIO_STA_RXOVERR (1<<5) // Received FIFO overrun error
|
||||
#define SDIO_STA_TXUNDERR (1<<4) // Transmit FIFO underrun error
|
||||
#define SDIO_STA_DTIMEOUT (1<<3) // Data timeout
|
||||
#define SDIO_STA_CTIMEOUT (1<<2) // Command response timeout. The Command TimeOut period has a fixed value of 64 SDIO_CK clock periods.
|
||||
#define SDIO_STA_DCRCFAIL (1<<1) // Data block sent/received (CRC check failed)
|
||||
#define SDIO_STA_CCRCFAIL (1<<0) // Command response received (CRC check failed)
|
||||
|
||||
#define SDIO_STA_CMD_ERROR_FLAGS (SDIO_STA_CTIMEOUT | SDIO_STA_CCRCFAIL)
|
||||
#define SDIO_STA_TRX_ERROR_FLAGS (SDIO_STA_STBITERR | SDIO_STA_RXOVERR | SDIO_STA_TXUNDERR | SDIO_STA_DTIMEOUT | SDIO_STA_DCRCFAIL)
|
||||
#define SDIO_STA_TRX_ACT_FLAGS (SDIO_STA_RXACT|SDIO_STA_TXACT)
|
||||
|
||||
// SDIO_ICR register bits (WO - write only)
|
||||
#define SDIO_ICR_CEATAENDC (1<<23) // clear CEATAEND flag
|
||||
#define SDIO_ICR_SDIOITC (1<<22) // clear SDIOIT flag
|
||||
#define SDIO_ICR_DBCKENDC (1<<10) // clear DBCKENDC flag
|
||||
#define SDIO_ICR_STBITERRC (1<<9) // clear STBITERRC flag
|
||||
#define SDIO_ICR_DATAENDC (1<<8) // clear DATAENDC flag
|
||||
#define SDIO_ICR_CMDSENTC (1<<7) // clear CMDSENTC flag
|
||||
#define SDIO_ICR_CMDRENDC (1<<6) // clear CMDREND flag
|
||||
#define SDIO_ICR_RXOVERRC (1<<5) // clear RXOVERR flag
|
||||
#define SDIO_ICR_TXUNDERRC (1<<4) // clear TXUNDERR flag
|
||||
#define SDIO_ICR_DTIMEOUTC (1<<3) // clear DTIMEOUT flag
|
||||
#define SDIO_ICR_CTIMEOUTC (1<<2) // clear CTIMEOUT flag
|
||||
#define SDIO_ICR_DCRCFAILC (1<<1) // clear DCRCFAIL flag
|
||||
#define SDIO_ICR_CCRCFAILC (1<<0) // clear CCRCFAIL flag
|
||||
|
||||
#define SDIO_ICR_CMD_FLAGS (SDIO_ICR_CEATAENDC | SDIO_ICR_SDIOITC | SDIO_ICR_CMDSENTC | SDIO_ICR_CMDRENDC | SDIO_ICR_CTIMEOUTC | SDIO_ICR_CCRCFAILC)
|
||||
#define SDIO_ICR_DATA_FLAGS (SDIO_ICR_DBCKENDC | SDIO_ICR_STBITERRC | SDIO_ICR_DATAENDC | SDIO_ICR_RXOVERRC | SDIO_ICR_TXUNDERRC | SDIO_ICR_DTIMEOUTC | SDIO_ICR_DCRCFAILC)
|
||||
|
||||
// SDIO_MASK register bits
|
||||
// Determines which status flags generate an interrupt request by setting the corresponding bit to 1b.
|
||||
#define SDIO_MASK_CEATAENDIE (1<<23) // enable CEATAEND interrupt
|
||||
#define SDIO_MASK_SDIOITIE (1<<22) // enable SDIOIT interrupt
|
||||
#define SDIO_MASK_RXDAVLIE (1<<21) // enable RXDAVL interrupt
|
||||
#define SDIO_MASK_TXDAVLIE (1<<20) // enable TXDAVL interrupt
|
||||
#define SDIO_MASK_RXFIFOEIE (1<<19) // enable RXFIFOE interrupt
|
||||
#define SDIO_MASK_TXFIFOEIE (1<<18) // enable TXFIFOE interrupt
|
||||
#define SDIO_MASK_RXFIFOFIE (1<<17) // enable RXFIFOF interrupt
|
||||
#define SDIO_MASK_TXFIFOFIE (1<<16) // enable TXFIFOF interrupt
|
||||
#define SDIO_MASK_RXFIFOHFIE (1<<15) // enable RXFIFOHF interrupt
|
||||
#define SDIO_MASK_TXFIFOHEIE (1<<14) // enable TXFIFOHE interrupt
|
||||
#define SDIO_MASK_RXACTIE (1<<13) // enable RXACT interrupt
|
||||
#define SDIO_MASK_TXACTIE (1<<12) // enable TXACT interrupt
|
||||
#define SDIO_MASK_CMDACTIE (1<<11) // enable CMDACT interrupt
|
||||
#define SDIO_MASK_DBCKENDIE (1<<10) // enable DBCKENDC interrupt
|
||||
#define SDIO_MASK_STBITERRIE (1<<9) // enable STBITERR interrupt
|
||||
#define SDIO_MASK_DATAENDIE (1<<8) // enable DATAENDC interrupt
|
||||
#define SDIO_MASK_CMDSENTIE (1<<7) // enable CMDSENTC interrupt
|
||||
#define SDIO_MASK_CMDRENDIE (1<<6) // enable CMDREND interrupt
|
||||
#define SDIO_MASK_RXOVERRIE (1<<5) // enable RXOVERR interrupt
|
||||
#define SDIO_MASK_TXUNDERRIE (1<<4) // enable TXUNDERR interrupt
|
||||
#define SDIO_MASK_DTIMEOUTIE (1<<3) // enable DTIMEOUT interrupt
|
||||
#define SDIO_MASK_CTIMEOUTIE (1<<2) // enable CTIMEOUT interrupt
|
||||
#define SDIO_MASK_DCRCFAILIE (1<<1) // enable DCRCFAIL interrupt
|
||||
#define SDIO_MASK_CCRCFAILIE (1<<0) // enable CCRCFAIL interrupt
|
||||
|
||||
|
||||
void sdio_enable(void);
|
||||
void sdio_disable(void);
|
||||
void sdio_begin(void);
|
||||
uint8_t sdio_cmd_send(uint16_t cmd_index_resp_type, uint32_t arg);
|
||||
void sdio_set_clock(uint32_t clk);
|
||||
void sdio_set_dbus_width(uint16_t bus_w);
|
||||
void sdio_set_dblock_size(uint8_t dbsize);
|
||||
//void sdio_trx_enable(uint8_t dir);
|
||||
inline void sdio_trx_enable(void)
|
||||
{
|
||||
SDIO->DCTRL |= SDIO_DCTRL_DTEN; // enable data transfer
|
||||
}
|
||||
|
||||
inline uint32_t sdio_cmd_xfer_ongoing(void) { return (SDIO->STA&SDIO_STA_CMDACT); }
|
||||
inline uint32_t sdio_cmd_complete(void) { return (SDIO->STA&SDIO_STA_CMDSENT); }
|
||||
|
||||
inline void sdio_setup_transfer(uint32_t dtimer, uint32_t dlen, uint16_t flags)
|
||||
{
|
||||
SDIO->ICR = SDIO_ICR_DATA_FLAGS; // clear data access relevant flags
|
||||
SDIO->DTIMER = dtimer;
|
||||
SDIO->DLEN = dlen;
|
||||
SDIO->DCTRL = flags;// | SDIO_DCTRL_DTEN; // enable data transfer
|
||||
}
|
||||
|
||||
/*
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
*/
|
||||
|
||||
#endif /* (STM32_HIGH_DENSITY) || (STM32_XL_DENSITY) */
|
||||
|
||||
#endif
|
@ -108,12 +108,6 @@ static inline uint32 systick_check_underflow(void) {
|
||||
return SYSTICK_BASE->CSR & SYSTICK_CSR_COUNTFLAG;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief prototype for systick_attach_callback
|
||||
*
|
||||
*/
|
||||
extern void systick_attach_callback(void (*callback)(void));
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
@ -785,22 +785,6 @@ static inline void timer_dma_disable_trg_req(timer_dev *dev) {
|
||||
*bb_perip(&(dev->regs).gen->DIER, TIMER_DIER_TDE_BIT) = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enable a timer's update DMA request
|
||||
* @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL
|
||||
*/
|
||||
static inline void timer_dma_enable_upd_req(timer_dev *dev) {
|
||||
*bb_perip(&(dev->regs).gen->DIER, TIMER_DIER_UDE_BIT) = 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Disable a timer's update DMA request
|
||||
* @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL
|
||||
*/
|
||||
static inline void timer_dma_disable_upd_req(timer_dev *dev) {
|
||||
*bb_perip(&(dev->regs).gen->DIER, TIMER_DIER_UDE_BIT) = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Enable a timer channel's DMA request.
|
||||
* @param dev Timer device, must have type TIMER_ADVANCED or TIMER_GENERAL
|
||||
@ -828,7 +812,6 @@ static inline void timer_dma_disable_req(timer_dev *dev, uint8 channel) {
|
||||
* @see timer_channel
|
||||
*/
|
||||
static inline void timer_enable_irq(timer_dev *dev, uint8 interrupt) {
|
||||
*bb_perip(&(dev->regs).adv->SR, interrupt) = 0; // clear interrupt flag
|
||||
*bb_perip(&(dev->regs).adv->DIER, interrupt) = 1;
|
||||
}
|
||||
|
||||
|
@ -439,8 +439,8 @@ static inline void usart_disable_all(void) {
|
||||
/**
|
||||
* @brief Transmit one character on a serial port.
|
||||
*
|
||||
* This function blocks until the character has been queued
|
||||
* for transmission.
|
||||
* This function blocks until the character has been successfully
|
||||
* transmitted.
|
||||
*
|
||||
* @param dev Serial port to send on.
|
||||
* @param byte Byte to transmit.
|
||||
|
@ -152,7 +152,7 @@ typedef struct dma_tube_reg_map {
|
||||
|
||||
#define DMA_ISR_TEIF (1 << DMA_ISR_TEIF_BIT)
|
||||
#define DMA_ISR_HTIF (1 << DMA_ISR_HTIF_BIT)
|
||||
#define DMA_ISR_TCIF (1 << DMA_ISR_TCIF_BIT)
|
||||
#define DMA_ISR_TCID (1 << DMA_ISR_TCIF_BIT)
|
||||
#define DMA_ISR_GIF (1 << DMA_ISR_GIF_BIT)
|
||||
|
||||
#define DMA_ISR_TEIF7_BIT 27
|
||||
@ -559,6 +559,7 @@ typedef enum dma_mode_flags {
|
||||
*
|
||||
* (It's not possible to fully configure a DMA stream on F2 with just
|
||||
* this information, so this interface is too tied to the F1.) */
|
||||
__deprecated
|
||||
void dma_setup_transfer(dma_dev *dev,
|
||||
dma_channel channel,
|
||||
__io void *peripheral_address,
|
||||
|
@ -345,12 +345,12 @@ static inline void usb_clear_status_out(uint8 ep) {
|
||||
/*
|
||||
* PMA conveniences
|
||||
*/
|
||||
/*
|
||||
|
||||
void usb_copy_to_pma(const uint8 *buf, uint16 len, uint16 pma_offset);
|
||||
void usb_copy_from_pma(uint8 *buf, uint16 len, uint16 pma_offset);
|
||||
*/
|
||||
static inline uint32 * usb_pma_ptr(uint32 offset) {
|
||||
return (uint32*)(USB_PMA_BASE + 2 * offset);
|
||||
|
||||
static inline void* usb_pma_ptr(uint32 offset) {
|
||||
return (void*)(USB_PMA_BASE + 2 * offset);
|
||||
}
|
||||
|
||||
/*
|
||||
@ -567,7 +567,7 @@ static inline uint16 usb_get_ep_rx_buf0_count(uint8 ep) {
|
||||
return usb_get_ep_tx_count(ep);
|
||||
}
|
||||
|
||||
//void usb_set_ep_rx_buf0_count(uint8 ep, uint16 count);
|
||||
void usb_set_ep_rx_buf0_count(uint8 ep, uint16 count);
|
||||
|
||||
static inline uint32* usb_ep_rx_buf1_count_ptr(uint8 ep) {
|
||||
return usb_ep_rx_count_ptr(ep);
|
||||
|
@ -36,7 +36,7 @@
|
||||
#ifndef _BOARD_GENERIC_STM32F103C_H_
|
||||
#define _BOARD_GENERIC_STM32F103C_H_
|
||||
|
||||
#define CYCLES_PER_MICROSECOND (F_CPU / 1000000U)
|
||||
#define CYCLES_PER_MICROSECOND 72
|
||||
#define SYSTICK_RELOAD_VAL (F_CPU/1000) - 1 /* takes a cycle to reload */
|
||||
|
||||
#define BOARD_NR_USARTS 3
|
||||
@ -70,10 +70,8 @@
|
||||
#define BOARD_JTDO_PIN 19
|
||||
#define BOARD_NJTRST_PIN 18
|
||||
|
||||
#define BOARD_USB_DISC_DEV NULL
|
||||
#define BOARD_USB_DISC_BIT NULL
|
||||
|
||||
#define LED_BUILTIN PC13
|
||||
#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 {
|
||||
|
@ -17,6 +17,4 @@ static const uint8_t MOSI = BOARD_SPI1_MOSI_PIN;
|
||||
static const uint8_t MISO = BOARD_SPI1_MISO_PIN;
|
||||
static const uint8_t SCK = BOARD_SPI1_SCK_PIN;
|
||||
|
||||
#define LED_BUILTIN PC13
|
||||
|
||||
#endif /* _VARIANT_ARDUINO_STM32_ */
|
||||
#endif /* _VARIANT_ARDUINO_STM32_ */
|
@ -48,13 +48,7 @@
|
||||
// works for F103 performance line MCUs, which is all that LeafLabs
|
||||
// currently officially supports).
|
||||
#ifndef BOARD_RCC_PLLMUL
|
||||
#if F_CPU==128000000
|
||||
#define BOARD_RCC_PLLMUL RCC_PLLMUL_16
|
||||
#elif F_CPU==72000000
|
||||
#define BOARD_RCC_PLLMUL RCC_PLLMUL_9
|
||||
#elif F_CPU==48000000
|
||||
#define BOARD_RCC_PLLMUL RCC_PLLMUL_6
|
||||
#endif
|
||||
#define BOARD_RCC_PLLMUL RCC_PLLMUL_9
|
||||
#endif
|
||||
|
||||
namespace wirish {
|
||||
@ -77,7 +71,7 @@ namespace wirish {
|
||||
#if F_CPU == 72000000
|
||||
rcc_set_prescaler(RCC_PRESCALER_USB, RCC_USB_SYSCLK_DIV_1_5);
|
||||
#elif F_CPU == 48000000
|
||||
rcc_set_prescaler(RCC_PRESCALER_USB, RCC_USB_SYSCLK_DIV_1);
|
||||
rcc_set_prescaler(RCC_PRESCALER_USB, RCC_USB_SYSCLK_DIV_1_5);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -83,6 +83,27 @@
|
||||
"version": "4.8.3-2014q1"
|
||||
}]
|
||||
},
|
||||
{
|
||||
"name": "Multi 4-in-1 STM32 Board",
|
||||
"architecture": "STM32F1",
|
||||
"version": "1.0.2",
|
||||
"category": "Contributed",
|
||||
"help": {
|
||||
"online": "https://github.com/pascallanger/DIY-Multiprotocol-TX-Module"
|
||||
},
|
||||
"url": "https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/raw/master/BootLoaders/package_multi_4in1_stm32_board_v1.0.2.tar.gz",
|
||||
"archiveFileName": "package_multi_4in1_stm32_board_v1.0.2.tar.gz",
|
||||
"checksum": "SHA-256:26D21DBD2FE80680AC523B8BCA24B3ECF2C2016BAC626826D20B651E11278287",
|
||||
"size": "103318646",
|
||||
"boards": [{
|
||||
"name": "Multi 4-in-1 (STM32F103C)"
|
||||
}],
|
||||
"toolsDependencies": [{
|
||||
"packager": "arduino",
|
||||
"name": "arm-none-eabi-gcc",
|
||||
"version": "4.8.3-2014q1"
|
||||
}]
|
||||
},
|
||||
{
|
||||
"name": "Multi 4-in-1 OrangeRX Board",
|
||||
"architecture": "orangerx",
|
||||
|
BIN
BootLoaders/package_multi_4in1_stm32_board_v1.0.2.tar.gz
Normal file
BIN
BootLoaders/package_multi_4in1_stm32_board_v1.0.2.tar.gz
Normal file
Binary file not shown.
Loading…
x
Reference in New Issue
Block a user