AP_HAL_QURT: Fix the SPI transfer special case where a send buffer is passed in even though it is a read transaction.

This commit is contained in:
Eric Katzfey 2024-11-13 16:36:53 -08:00 committed by Peter Barker
parent f07df393be
commit 1e99226fd9
1 changed files with 6 additions and 0 deletions

View File

@ -67,6 +67,12 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
return transfer_fullduplex(send, (uint8_t*) send, send_len);
}
// Special case handling. This can happen when a send buffer is specified
// even though we are doing only a read.
if (send == recv && send_len == recv_len) {
return transfer_fullduplex(send, recv, send_len);
}
// This is a read transaction
uint8_t buf[send_len+recv_len];
if (send_len > 0) {