mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_PX4: avoid bounce buffers for SPI when possible
This commit is contained in:
parent
f3d401abb9
commit
37a9a78725
@ -146,7 +146,7 @@ bool SPIDevice::set_speed(AP_HAL::Device::Speed speed)
|
||||
/*
|
||||
low level transfer function
|
||||
*/
|
||||
void SPIDevice::do_transfer(uint8_t *send, uint8_t *recv, uint32_t len)
|
||||
void SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
|
||||
{
|
||||
/*
|
||||
to accomodate the method in PX4 drivers of using interrupt
|
||||
@ -187,6 +187,11 @@ void SPIDevice::do_transfer(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)
|
||||
{
|
||||
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];
|
||||
if (send_len > 0) {
|
||||
memcpy(buf, send, send_len);
|
||||
|
@ -62,7 +62,7 @@ public:
|
||||
bool set_speed(AP_HAL::Device::Speed speed) override;
|
||||
|
||||
// low level transfer function
|
||||
void do_transfer(uint8_t *send, uint8_t *recv, uint32_t len);
|
||||
void do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len);
|
||||
|
||||
/* See AP_HAL::Device::transfer() */
|
||||
bool transfer(const uint8_t *send, uint32_t send_len,
|
||||
|
Loading…
Reference in New Issue
Block a user