HAL_AVR: added bulk transfer() method

this is quite a lot faster than the byte at a time method
This commit is contained in:
Andrew Tridgell 2013-01-12 22:13:04 +11:00
parent 6415f00ce3
commit b5b7fd2f9a
4 changed files with 38 additions and 3 deletions

View File

@ -69,6 +69,12 @@ inline uint8_t AVRSPI0DeviceDriver::_transfer(uint8_t data) {
return read_spdr;
}
void AVRSPI0DeviceDriver::transfer(const uint8_t *tx, uint16_t len) {
for (uint16_t i = 0; i < len; i++) {
_transfer(tx[i]);
}
}
void AVRSPI0DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
uint16_t len) {
_cs_assert();

View File

@ -1,3 +1,4 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
@ -95,4 +96,9 @@ uint8_t AVRSPI2DeviceDriver::transfer(uint8_t data) {
return _transfer(data);
}
void AVRSPI2DeviceDriver::transfer(const uint8_t *data, uint16_t len) {
while (len--)
_transfer(*data++);
}
#endif

View File

@ -1,3 +1,4 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
@ -73,13 +74,27 @@ uint8_t AVRSPI3DeviceDriver::_transfer(uint8_t data) {
return UDR3;
}
void AVRSPI3DeviceDriver::_transfer(const uint8_t *data, uint16_t len) {
while (len--) {
/* Wait for empty transmit buffer */
while ( !( UCSR3A & _BV(UDRE3)) ) ;
/* Put data into buffer, sends the data */
UDR3 = *data++;
/* Wait for data to be received */
while ( !(UCSR3A & _BV(RXC3)) ) ;
// dummy read of UDR3 to complete
UDR3;
}
}
void AVRSPI3DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
uint16_t len) {
_cs_assert();
if (rx == NULL) {
for (uint16_t i = 0; i < len; i++) {
_transfer(tx[i]);
}
_transfer(tx, len);
} else {
for (uint16_t i = 0; i < len; i++) {
rx[i] = _transfer(tx[i]);
@ -100,4 +115,8 @@ uint8_t AVRSPI3DeviceDriver::transfer(uint8_t data) {
return _transfer(data);
}
void AVRSPI3DeviceDriver::transfer(const uint8_t *data, uint16_t len) {
_transfer(data, len);
}
#endif

View File

@ -25,6 +25,7 @@ public:
void cs_assert();
void cs_release();
uint8_t transfer(uint8_t data);
void transfer(const uint8_t *data, uint16_t len);
private:
void _cs_assert();
@ -59,6 +60,7 @@ public:
void cs_assert();
void cs_release();
uint8_t transfer(uint8_t data);
void transfer(const uint8_t *data, uint16_t len);
private:
void _cs_assert();
@ -92,11 +94,13 @@ public:
void cs_assert();
void cs_release();
uint8_t transfer(uint8_t data);
void transfer(const uint8_t *data, uint16_t len);
private:
void _cs_assert();
void _cs_release();
uint8_t _transfer(uint8_t data);
void _transfer(const uint8_t *data, uint16_t size);
static AP_HAL_AVR::AVRSemaphore _semaphore;
AP_HAL_AVR::AVRDigitalSource *_cs_pin;