mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 02:28:29 -04:00
AP_HAL_AVR: spi transaction handle null RX properly
This commit is contained in:
parent
992de8c2b9
commit
3153105682
@ -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();
|
||||
}
|
||||
|
@ -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();
|
||||
}
|
||||
|
@ -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…
Reference in New Issue
Block a user