From 1e99226fd96a4c90113c819e7d9db29679210085 Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Wed, 13 Nov 2024 16:36:53 -0800 Subject: [PATCH] AP_HAL_QURT: Fix the SPI transfer special case where a send buffer is passed in even though it is a read transaction. --- libraries/AP_HAL_QURT/SPIDevice.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_HAL_QURT/SPIDevice.cpp b/libraries/AP_HAL_QURT/SPIDevice.cpp index 616cf6a76f..a4fcdc6660 100644 --- a/libraries/AP_HAL_QURT/SPIDevice.cpp +++ b/libraries/AP_HAL_QURT/SPIDevice.cpp @@ -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) {