Skip to content

Commit

Permalink
AP_HAL_QURT: Fix the SPI transfer special case where a send buffer is…
Browse files Browse the repository at this point in the history
… passed in even though it is a read transaction.
  • Loading branch information
katzfey committed Nov 14, 2024
1 parent f07df39 commit e053418
Showing 1 changed file with 6 additions and 0 deletions.
6 changes: 6 additions & 0 deletions libraries/AP_HAL_QURT/SPIDevice.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down

0 comments on commit e053418

Please sign in to comment.