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. 6
      libraries/AP_HAL_AVR/SPIDevice_SPI0.cpp
  2. 6
      libraries/AP_HAL_AVR/SPIDevice_SPI2.cpp
  3. 6
      libraries/AP_HAL_AVR/SPIDevice_SPI3.cpp

6
libraries/AP_HAL_AVR/SPIDevice_SPI0.cpp

@ -72,9 +72,15 @@ inline uint8_t AVRSPI0DeviceDriver::_transfer(uint8_t data) {
void AVRSPI0DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, void AVRSPI0DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
uint16_t len) { uint16_t len) {
_cs_assert(); _cs_assert();
if (rx == NULL) {
for (uint16_t i = 0; i < len; i++) {
_transfer(tx[i]);
}
} else {
for (uint16_t i = 0; i < len; i++) { for (uint16_t i = 0; i < len; i++) {
rx[i] = _transfer(tx[i]); rx[i] = _transfer(tx[i]);
} }
}
_cs_release(); _cs_release();
} }

6
libraries/AP_HAL_AVR/SPIDevice_SPI2.cpp

@ -71,9 +71,15 @@ inline uint8_t AVRSPI2DeviceDriver::_transfer(uint8_t data) {
void AVRSPI2DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, void AVRSPI2DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
uint16_t len) { uint16_t len) {
_cs_assert(); _cs_assert();
if (rx == NULL) {
for (uint16_t i = 0; i < len; i++) {
_transfer(tx[i]);
}
} else {
for (uint16_t i = 0; i < len; i++) { for (uint16_t i = 0; i < len; i++) {
rx[i] = _transfer(tx[i]); rx[i] = _transfer(tx[i]);
} }
}
_cs_release(); _cs_release();
} }

6
libraries/AP_HAL_AVR/SPIDevice_SPI3.cpp

@ -76,9 +76,15 @@ uint8_t AVRSPI3DeviceDriver::_transfer(uint8_t data) {
void AVRSPI3DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, void AVRSPI3DeviceDriver::transaction(const uint8_t *tx, uint8_t *rx,
uint16_t len) { uint16_t len) {
_cs_assert(); _cs_assert();
if (rx == NULL) {
for (uint16_t i = 0; i < len; i++) {
_transfer(tx[i]);
}
} else {
for (uint16_t i = 0; i < len; i++) { for (uint16_t i = 0; i < len; i++) {
rx[i] = _transfer(tx[i]); rx[i] = _transfer(tx[i]);
} }
}
_cs_release(); _cs_release();
} }

Loading…
Cancel
Save