Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SPI Full Duplex #29614

Merged
merged 8 commits into from
Apr 2, 2025
Merged
2 changes: 1 addition & 1 deletion libraries/AP_Baro/AP_Baro_BMP388.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -245,7 +245,7 @@ bool AP_Baro_BMP388::read_registers(uint8_t reg, uint8_t *data, uint8_t len)
uint8_t b[len+2];
b[0] = reg | 0x80;
memset(&b[1], 0, len+1);
if (!dev->transfer(b, len+2, b, len+2)) {
if (!dev->transfer_fullduplex(b, len+2)) {
return false;
}
memcpy(data, &b[2], len);
Expand Down
17 changes: 15 additions & 2 deletions libraries/AP_HAL/Device.h
Original file line number Diff line number Diff line change
Expand Up @@ -116,14 +116,27 @@ class AP_HAL::Device {
virtual bool set_speed(Speed speed) = 0;

/*
* Core transfer function. This does a single bus transaction which
* sends send_len bytes and receives recv_len bytes back from the slave.
* This does a single bus transaction which sends send_len bytes,
* then receives recv_len bytes back from the slave. Operation is
* half-duplex independent of bus type.
*
* Return: true on a successful transfer, false on failure.
*/
virtual bool transfer(const uint8_t *send, uint32_t send_len,
uint8_t *recv, uint32_t recv_len) = 0;

/*
* Core transfer function. This does a single bus transaction which
* sends len bytes and receives len bytes back from the slave.
* On full-duplex buses (e.g. SPI), the transfer is full-duplex,
* unlike `transfer`.
* DMA-optimized on some implementations
*
* Return: true on a successful transfer, false on failure.
*/
virtual bool transfer_fullduplex(uint8_t *send_recv, uint32_t len) {
return transfer(send_recv, len, send_recv, len);
}

/*
* Sets the required flags before transaction starts
Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_HAL/SPIDevice.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,14 @@ class SPIDevice : public Device {
virtual bool transfer_fullduplex(const uint8_t *send, uint8_t *recv,
uint32_t len) = 0;

/*
* Like #transfer(), but len bytes are both transmitted and received from/into @send_recv.
* This function is optimized for DMA-enabled multi-transfers without buffer copying
*/
bool transfer_fullduplex(uint8_t *send_recv, uint32_t len) override {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is a copy of the one in Device.h, why is this here?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Removed, hopefully it's not necessary for Linux or something :)

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It can't be removed or loads of hals do not build

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

which HAL doesn't build without the transfer_fullduplex() in AP_HAL/SPIDevice.h?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

QURT at least had a build failure on CI. It seems to be a Clang warning that you have to override all the variations with different arguments of a particular function name to avoid ambiguity: https://stackoverflow.com/a/9995567

 [10/933] Compiling libraries/AC_AttitudeControl/AC_CommandModel.cpp
In file included from ../../libraries/AC_AttitudeControl/AC_CommandModel.cpp:1:
In file included from ../../libraries/AC_AttitudeControl/AC_CommandModel.h:6:
In file included from ../../libraries/AP_Param/AP_Param.h:27:
In file included from ../../libraries/AP_HAL/AP_HAL.h:8:
In file included from ../../libraries/AP_HAL/AP_HAL_Main.h:19:
In file included from ../../libraries/AP_HAL/HAL.h:11:
../../libraries/AP_HAL/SPIDevice.h:45:18: fatal error: 'AP_HAL::SPIDevice::transfer_fullduplex' hides overloaded virtual function [-Woverloaded-virtual]
    virtual bool transfer_fullduplex(const uint8_t *send, uint8_t *recv,
                 ^
../../libraries/AP_HAL/Device.h:137:18: note: hidden overloaded virtual function 'AP_HAL::Device::transfer_fullduplex' declared here: different number of parameters (2 vs 3)
    virtual bool transfer_fullduplex(uint8_t *send_recv, uint32_t len) {
                 ^
1 error generated.

I personally would just mark it as pure virtual = 0 instead of duplicating the implementation. More C++ learning!

return transfer(send_recv, len, send_recv, len);
}

/*
* send N bytes of clock pulses without taking CS. This is used
* when initialising microSD interfaces over SPI
Expand Down
9 changes: 9 additions & 0 deletions libraries/AP_HAL_ChibiOS/SPIDevice.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -292,6 +292,7 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
if (!bus.semaphore.check_owner()) {
return false;
}
// callers should prefer transfer_fullduplex() to relying on this semantic
if ((send_len == recv_len && send == recv) || !send || !recv) {
// simplest cases, needed for DMA
return do_transfer(send, recv, recv_len?recv_len:send_len);
Expand Down Expand Up @@ -324,6 +325,14 @@ bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t
return ret;
}

bool SPIDevice::transfer_fullduplex(uint8_t *send_recv, uint32_t len)
{
if (!bus.semaphore.check_owner()) {
return false;
}
return do_transfer(send_recv, send_recv, len);
}

AP_HAL::Semaphore *SPIDevice::get_semaphore()
{
return &bus.semaphore;
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_HAL_ChibiOS/SPIDevice.h
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,9 @@ class SPIDevice : public AP_HAL::SPIDevice {
bool transfer_fullduplex(const uint8_t *send, uint8_t *recv,
uint32_t len) override;

/* See AP_HAL::SPIDevice::transfer_fullduplex() */
bool transfer_fullduplex(uint8_t *send_recv, uint32_t len) override;

/*
Links the bank select callback to the spi bus, so that even when
used outside of the driver bank selection can be done.
Expand Down
7 changes: 6 additions & 1 deletion libraries/AP_HAL_ESP32/SPIDevice.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
#ifdef SPIDEBUG
printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__);
#endif
if ((send_len == recv_len && send == recv) || !send || !recv) {
if (!send || !recv) {
// simplest cases
transfer_fullduplex(send, recv, recv_len?recv_len:send_len);
return true;
Expand All @@ -131,6 +131,11 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
return true;
}

bool SPIDevice::transfer_fullduplex(uint8_t *send_recv, uint32_t len)
{
return transfer_fullduplex(send_recv, send_recv, len);
}

bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len)
{
#ifdef SPIDEBUG
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_HAL_ESP32/SPIDevice.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,8 @@ class SPIDevice : public AP_HAL::SPIDevice
uint8_t *recv, uint32_t recv_len) override;
bool transfer_fullduplex(const uint8_t *send, uint8_t *recv,
uint32_t len) override;
/* See AP_HAL::SPIDevice::transfer_fullduplex() */
bool transfer_fullduplex(uint8_t *send_recv, uint32_t len) override;
AP_HAL::Semaphore *get_semaphore() override;
AP_HAL::Device::PeriodicHandle register_periodic_callback(
uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_HAL_Linux/SPIDevice.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -291,6 +291,10 @@ bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv,
return true;
}

bool SPIDevice::transfer_fullduplex(uint8_t *send_recv, uint32_t len)
{
return transfer_fullduplex(send_recv, send_recv, len);
}

void SPIDevice::_cs_assert()
{
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_HAL_Linux/SPIDevice.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,9 @@ class SPIDevice : public AP_HAL::SPIDevice {
bool transfer_fullduplex(const uint8_t *send, uint8_t *recv,
uint32_t len) override;

/* See AP_HAL::SPIDevice::transfer_fullduplex() */
bool transfer_fullduplex(uint8_t *send_recv, uint32_t len) override;

/* See AP_HAL::Device::get_semaphore() */
AP_HAL::Semaphore *get_semaphore() override;

Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_HAL_SITL/SPIDevice.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,9 @@ class SPIDevice : public AP_HAL::SPIDevice {
abort();
}

bool transfer_fullduplex(uint8_t *send_recv, uint32_t len) override {
abort();
}

AP_HAL::Semaphore *get_semaphore() override;

Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_InertialSensor/AP_InertialSensor_ADIS1647x.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -332,7 +332,7 @@ void AP_InertialSensor_ADIS1647x::read_sensor16(void)
WITH_SEMAPHORE(dev->get_semaphore());
data.cmd[0] = REG_GLOB_CMD;
DEBUG_SET_PIN(2, 1);
if (!dev->transfer((const uint8_t *)&data, sizeof(data), (uint8_t *)&data, sizeof(data))) {
if (!dev->transfer_fullduplex((uint8_t *)&data, sizeof(data))) {
break;
}
DEBUG_SET_PIN(2, 0);
Expand Down Expand Up @@ -424,7 +424,7 @@ void AP_InertialSensor_ADIS1647x::read_sensor32(void)
WITH_SEMAPHORE(dev->get_semaphore());
data.cmd[0] = REG_GLOB_CMD;
DEBUG_SET_PIN(2, 1);
if (!dev->transfer((const uint8_t *)&data, sizeof(data), (uint8_t *)&data, sizeof(data))) {
if (!dev->transfer_fullduplex((uint8_t *)&data, sizeof(data))) {
break;
}
DEBUG_SET_PIN(2, 0);
Expand Down Expand Up @@ -516,7 +516,7 @@ void AP_InertialSensor_ADIS1647x::read_sensor32_delta(void)
WITH_SEMAPHORE(dev->get_semaphore());
data.cmd[0] = REG_GLOB_CMD;
DEBUG_SET_PIN(2, 1);
if (!dev->transfer((const uint8_t *)&data, sizeof(data), (uint8_t *)&data, sizeof(data))) {
if (!dev->transfer_fullduplex((uint8_t *)&data, sizeof(data))) {
break;
}
DEBUG_SET_PIN(2, 0);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ bool AP_InertialSensor_BMI088::read_accel_registers(uint8_t reg, uint8_t *data,
uint8_t b[len+2];
b[0] = reg | 0x80;
memset(&b[1], 0, len+1);
if (!dev_accel->transfer(b, len+2, b, len+2)) {
if (!dev_accel->transfer_fullduplex(b, len+2)) {
return false;
}
memcpy(data, &b[2], len);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_InertialSensor/AP_InertialSensor_BMI270.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -242,7 +242,7 @@ bool AP_InertialSensor_BMI270::read_registers(uint8_t reg, uint8_t *data, uint8_
uint8_t b[len+2];
b[0] = reg | 0x80;
memset(&b[1], 0, len+1);
if (!_dev->transfer(b, len+2, b, len+2)) {
if (!_dev->transfer_fullduplex(b, len+2)) {
return false;
}
memcpy(data, &b[2], len);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -771,7 +771,7 @@ void AP_InertialSensor_Invensense::_read_fifo()
goto check_registers;
}
memset(rx, 0, n * MPU_SAMPLE_SIZE);
if (!_dev->transfer(rx, n * MPU_SAMPLE_SIZE, rx, n * MPU_SAMPLE_SIZE)) {
if (!_dev->transfer_fullduplex(rx, n * MPU_SAMPLE_SIZE)) {
if (!hal.scheduler->in_expected_delay()) {
debug("MPU60x0: error in fifo read %u bytes\n", n * MPU_SAMPLE_SIZE);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -506,7 +506,7 @@ void AP_InertialSensor_Invensensev2::_read_fifo()
goto check_registers;
}
memset(rx, 0, n * INV2_SAMPLE_SIZE);
if (!_dev->transfer(rx, n * INV2_SAMPLE_SIZE, rx, n * INV2_SAMPLE_SIZE)) {
if (!_dev->transfer_fullduplex(rx, n * INV2_SAMPLE_SIZE)) {
if (!hal.scheduler->in_expected_delay()) {
debug("INV2: error in fifo read %u bytes\n", n * INV2_SAMPLE_SIZE);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -599,7 +599,7 @@ void AP_InertialSensor_Invensensev3::read_fifo()
tfr_buffer[0] = reg_data | BIT_READ_FLAG;
// transfer will also be sending data, make sure that data is zero
memset(tfr_buffer + 1, 0, n * fifo_sample_size);
if (!dev->transfer(tfr_buffer, n * fifo_sample_size + 1, tfr_buffer, n * fifo_sample_size + 1)) {
if (!dev->transfer_fullduplex(tfr_buffer, n * fifo_sample_size + 1)) {
goto check_registers;
}
samples = tfr_buffer + 1;
Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_InertialSensor/AP_InertialSensor_SCHA63T.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -428,12 +428,12 @@ bool AP_InertialSensor_SCHA63T::read_register(uint8_t uno_due, reg_scha63t reg_a
switch (uno_due) {
case SCHA63T_UNO:
memcpy(buf, cmd, 4);
ret = dev_uno->transfer(buf, 4, buf, 4);
ret = dev_uno->transfer_fullduplex(buf, 4);
memcpy(val, buf, 4);
break;
case SCHA63T_DUE:
memcpy(buf, cmd, 4);
ret = dev_due->transfer(buf, 4, buf, 4);
ret = dev_due->transfer_fullduplex(buf, 4);
memcpy(val, buf, 4);
break;
default:
Expand Down Expand Up @@ -467,12 +467,12 @@ bool AP_InertialSensor_SCHA63T::write_register(uint8_t uno_due, reg_scha63t reg_
switch (uno_due) {
case SCHA63T_UNO:
memcpy(buf, cmd, 4);
ret = dev_uno->transfer(buf, 4, buf, 4);
ret = dev_uno->transfer_fullduplex(buf, 4);
memcpy(res, buf, 4);
break;
case SCHA63T_DUE:
memcpy(buf, cmd, 4);
ret = dev_due->transfer(buf, 4, buf, 4);
ret = dev_due->transfer_fullduplex(buf, 4);
memcpy(res, buf, 4);
break;
default:
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_OSD/AP_OSD_MAX7456.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,7 @@ bool AP_OSD_MAX7456::check_font_char(uint8_t chr, const uint8_t* font_data)
buffer_add_cmd(MAX7456ADD_CMDO, 0xFF);
}
_dev->get_semaphore()->take_blocking();
_dev->transfer(buffer, buffer_offset, buffer, buffer_offset);
_dev->transfer_fullduplex(buffer, buffer_offset);
_dev->get_semaphore()->give();

//skip response from MAX7456ADD_VM0/MAX7456ADD_CMAH...
Expand Down
Loading