Browse Source

AP_HAL_AVR: spi transaction handle null RX properly

master
Pat Hickey 12 years ago committed by Andrew Tridgell
parent
commit
3153105682
  1. 10
      libraries/AP_HAL_AVR/SPIDevice_SPI0.cpp
  2. 10
      libraries/AP_HAL_AVR/SPIDevice_SPI2.cpp
  3. 10
      libraries/AP_HAL_AVR/SPIDevice_SPI3.cpp

10
libraries/AP_HAL_AVR/SPIDevice_SPI0.cpp

@ -72,8 +72,14 @@ inline uint8_t AVRSPI0DeviceDriver::_transfer(uint8_t data) { @@ -72,8 +72,14 @@ inline uint8_t AVRSPI0DeviceDriver::_transfer(uint8_t data) {
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]);
if (rx == NULL) {
for (uint16_t i = 0; i < len; i++) {
_transfer(tx[i]);
}
} else {
for (uint16_t i = 0; i < len; i++) {
rx[i] = _transfer(tx[i]);
}
}
_cs_release();
}

10
libraries/AP_HAL_AVR/SPIDevice_SPI2.cpp

@ -71,8 +71,14 @@ inline uint8_t AVRSPI2DeviceDriver::_transfer(uint8_t data) { @@ -71,8 +71,14 @@ inline uint8_t AVRSPI2DeviceDriver::_transfer(uint8_t data) {
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]);
if (rx == NULL) {
for (uint16_t i = 0; i < len; i++) {
_transfer(tx[i]);
}
} else {
for (uint16_t i = 0; i < len; i++) {
rx[i] = _transfer(tx[i]);
}
}
_cs_release();
}

10
libraries/AP_HAL_AVR/SPIDevice_SPI3.cpp

@ -76,8 +76,14 @@ uint8_t AVRSPI3DeviceDriver::_transfer(uint8_t data) { @@ -76,8 +76,14 @@ uint8_t AVRSPI3DeviceDriver::_transfer(uint8_t data) {
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]);
if (rx == NULL) {
for (uint16_t i = 0; i < len; i++) {
_transfer(tx[i]);
}
} else {
for (uint16_t i = 0; i < len; i++) {
rx[i] = _transfer(tx[i]);
}
}
_cs_release();
}

Loading…
Cancel
Save