Browse Source

AP_HAL_AVR: Implement bulk SPI transaction

mission-4.1.18
Pat Hickey 12 years ago committed by Andrew Tridgell
parent
commit
4fe889c9c5
  1. 27
      libraries/AP_HAL_AVR/SPIDevice_SPI0.cpp
  2. 27
      libraries/AP_HAL_AVR/SPIDevice_SPI2.cpp
  3. 27
      libraries/AP_HAL_AVR/SPIDevice_SPI3.cpp
  4. 20
      libraries/AP_HAL_AVR/SPIDevices.h

27
libraries/AP_HAL_AVR/SPIDevice_SPI0.cpp

@ -36,7 +36,7 @@ AP_HAL::Semaphore* AVRSPI0DeviceDriver::get_semaphore() {
return &_semaphore; return &_semaphore;
} }
void AVRSPI0DeviceDriver::cs_assert() { inline void AVRSPI0DeviceDriver::_cs_assert() {
const uint8_t valid_spcr_mask = const uint8_t valid_spcr_mask =
(_BV(CPOL) | _BV(CPHA) | _BV(SPR1) | _BV(SPR0)); (_BV(CPOL) | _BV(CPHA) | _BV(SPR1) | _BV(SPR0));
uint8_t new_spcr = SPCR | (_spcr & valid_spcr_mask); uint8_t new_spcr = SPCR | (_spcr & valid_spcr_mask);
@ -49,11 +49,11 @@ void AVRSPI0DeviceDriver::cs_assert() {
_cs_pin->write(0); _cs_pin->write(0);
} }
void AVRSPI0DeviceDriver::cs_release() { inline void AVRSPI0DeviceDriver::_cs_release() {
_cs_pin->write(1); _cs_pin->write(1);
} }
uint8_t AVRSPI0DeviceDriver::transfer(uint8_t data) { inline uint8_t AVRSPI0DeviceDriver::_transfer(uint8_t data) {
if (spi0_transferflag) { if (spi0_transferflag) {
hal.scheduler->panic(PSTR("PANIC: SPI0 transfer collision")); hal.scheduler->panic(PSTR("PANIC: SPI0 transfer collision"));
} }
@ -69,4 +69,25 @@ uint8_t AVRSPI0DeviceDriver::transfer(uint8_t data) {
return read_spdr; return read_spdr;
} }
void AVRSPI0DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
uint16_t len) {
_cs_assert();
for (uint16_t i = 0; i < len; i++) {
rx[i] = _transfer(tx[i]);
}
_cs_release();
}
void AVRSPI0DeviceDriver::cs_assert() {
_cs_assert();
}
void AVRSPI0DeviceDriver::cs_release() {
_cs_release();
}
uint8_t AVRSPI0DeviceDriver::transfer(uint8_t data) {
return _transfer(data);
}
#endif #endif

27
libraries/AP_HAL_AVR/SPIDevice_SPI2.cpp

@ -38,7 +38,7 @@ AP_HAL::Semaphore* AVRSPI2DeviceDriver::get_semaphore() {
return &_semaphore; return &_semaphore;
} }
void AVRSPI2DeviceDriver::cs_assert() { inline void AVRSPI2DeviceDriver::_cs_assert() {
/* set the device UCSRnC configuration bits. /* set the device UCSRnC configuration bits.
* only sets data order, clock phase, and clock polarity bits (lowest * only sets data order, clock phase, and clock polarity bits (lowest
* three bits) */ * three bits) */
@ -50,11 +50,11 @@ void AVRSPI2DeviceDriver::cs_assert() {
_cs_pin->write(0); _cs_pin->write(0);
} }
void AVRSPI2DeviceDriver::cs_release() { inline void AVRSPI2DeviceDriver::_cs_release() {
_cs_pin->write(1); _cs_pin->write(1);
} }
uint8_t AVRSPI2DeviceDriver::transfer(uint8_t data) { inline uint8_t AVRSPI2DeviceDriver::_transfer(uint8_t data) {
/* Wait for empty transmit buffer */ /* Wait for empty transmit buffer */
while ( !( UCSR2A & _BV(UDRE2)) ) ; while ( !( UCSR2A & _BV(UDRE2)) ) ;
@ -68,4 +68,25 @@ uint8_t AVRSPI2DeviceDriver::transfer(uint8_t data) {
return UDR2; return UDR2;
} }
void AVRSPI2DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
uint16_t len) {
_cs_assert();
for (uint16_t i = 0; i < len; i++) {
rx[i] = _transfer(tx[i]);
}
_cs_release();
}
void AVRSPI2DeviceDriver::cs_assert() {
_cs_assert();
}
void AVRSPI2DeviceDriver::cs_release() {
_cs_release();
}
uint8_t AVRSPI2DeviceDriver::transfer(uint8_t data) {
return _transfer(data);
}
#endif #endif

27
libraries/AP_HAL_AVR/SPIDevice_SPI3.cpp

@ -43,7 +43,7 @@ AP_HAL::Semaphore* AVRSPI3DeviceDriver::get_semaphore() {
return &_semaphore; return &_semaphore;
} }
void AVRSPI3DeviceDriver::cs_assert() { void AVRSPI3DeviceDriver::_cs_assert() {
/* set the device UCSRnC configuration bits. /* set the device UCSRnC configuration bits.
* only sets data order, clock phase, and clock polarity bits (lowest * only sets data order, clock phase, and clock polarity bits (lowest
* three bits) */ * three bits) */
@ -55,11 +55,11 @@ void AVRSPI3DeviceDriver::cs_assert() {
_cs_pin->write(0); _cs_pin->write(0);
} }
void AVRSPI3DeviceDriver::cs_release() { void AVRSPI3DeviceDriver::_cs_release() {
_cs_pin->write(1); _cs_pin->write(1);
} }
uint8_t AVRSPI3DeviceDriver::transfer(uint8_t data) { uint8_t AVRSPI3DeviceDriver::_transfer(uint8_t data) {
/* Wait for empty transmit buffer */ /* Wait for empty transmit buffer */
while ( !( UCSR3A & _BV(UDRE3)) ) ; while ( !( UCSR3A & _BV(UDRE3)) ) ;
@ -73,4 +73,25 @@ uint8_t AVRSPI3DeviceDriver::transfer(uint8_t data) {
return UDR3; return UDR3;
} }
void AVRSPI3DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
uint16_t len) {
_cs_assert();
for (uint16_t i = 0; i < len; i++) {
rx[i] = _transfer(tx[i]);
}
_cs_release();
}
void AVRSPI3DeviceDriver::cs_assert() {
_cs_assert();
}
void AVRSPI3DeviceDriver::cs_release() {
_cs_release();
}
uint8_t AVRSPI3DeviceDriver::transfer(uint8_t data) {
return _transfer(data);
}
#endif #endif

20
libraries/AP_HAL_AVR/SPIDevices.h

@ -19,11 +19,18 @@ public:
void init(); void init();
AP_HAL::Semaphore* get_semaphore(); AP_HAL::Semaphore* get_semaphore();
void transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
void cs_assert(); void cs_assert();
void cs_release(); void cs_release();
uint8_t transfer(uint8_t data); uint8_t transfer(uint8_t data);
private: private:
void _cs_assert();
void _cs_release();
uint8_t _transfer(uint8_t data);
static AP_HAL_AVR::AVRSemaphore _semaphore; static AP_HAL_AVR::AVRSemaphore _semaphore;
AP_HAL_AVR::AVRDigitalSource *_cs_pin; AP_HAL_AVR::AVRDigitalSource *_cs_pin;
@ -46,11 +53,18 @@ public:
void init(); void init();
AP_HAL::Semaphore* get_semaphore(); AP_HAL::Semaphore* get_semaphore();
void transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
void cs_assert(); void cs_assert();
void cs_release(); void cs_release();
uint8_t transfer(uint8_t data); uint8_t transfer(uint8_t data);
private: private:
void _cs_assert();
void _cs_release();
uint8_t _transfer(uint8_t data);
static AP_HAL_AVR::AVRSemaphore _semaphore; static AP_HAL_AVR::AVRSemaphore _semaphore;
AP_HAL_AVR::AVRDigitalSource *_cs_pin; AP_HAL_AVR::AVRDigitalSource *_cs_pin;
@ -72,11 +86,17 @@ public:
void init(); void init();
AP_HAL::Semaphore* get_semaphore(); AP_HAL::Semaphore* get_semaphore();
void transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
void cs_assert(); void cs_assert();
void cs_release(); void cs_release();
uint8_t transfer(uint8_t data); uint8_t transfer(uint8_t data);
private: private:
void _cs_assert();
void _cs_release();
uint8_t _transfer(uint8_t data);
static AP_HAL_AVR::AVRSemaphore _semaphore; static AP_HAL_AVR::AVRSemaphore _semaphore;
AP_HAL_AVR::AVRDigitalSource *_cs_pin; AP_HAL_AVR::AVRDigitalSource *_cs_pin;

Loading…
Cancel
Save