mirror of https://github.com/ArduPilot/ardupilot
Revert "HAL_PX4: Add input parameter check."
This reverts commit 5f41b09fde
.
This change is completely incorrect. It is quite common to do SPI
transfers with zero send bytes, and is required for many sensors and
other devices
This commit is contained in:
parent
dec954bb0c
commit
05d9455f87
|
@ -187,18 +187,15 @@ void SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
|
|||
bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
|
||||
uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
// Check input parameters
|
||||
if(0 == send_len || nullptr == send || (nullptr == recv && 0 != recv_len)) {
|
||||
return false;
|
||||
}
|
||||
if (send_len == recv_len && send == recv) {
|
||||
// simplest cases, needed for DMA
|
||||
do_transfer(send, recv, recv_len);
|
||||
return true;
|
||||
}
|
||||
uint8_t buf[send_len+recv_len];
|
||||
memcpy(buf, send, send_len); // Set Register number, etc..
|
||||
|
||||
if (send_len > 0) {
|
||||
memcpy(buf, send, send_len);
|
||||
}
|
||||
if (recv_len > 0) {
|
||||
memset(&buf[send_len], 0, recv_len);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue