mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
HAL_ChibiOS: added optional polled SPI mode
This commit is contained in:
parent
9a2c19285d
commit
807d9e4b92
@ -174,11 +174,19 @@ void SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#if defined(HAL_SPI_USE_POLLED)
|
||||||
|
for (uint16_t i=0; i<len; i++) {
|
||||||
|
uint8_t ret = spiPolledExchange(spi_devices[device_desc.bus].driver, send?send[i]:0);
|
||||||
|
if (recv) {
|
||||||
|
recv[i] = ret;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#else
|
||||||
bus.bouncebuffer_setup(send, len, recv, len);
|
bus.bouncebuffer_setup(send, len, recv, len);
|
||||||
|
|
||||||
spiExchange(spi_devices[device_desc.bus].driver, len, send, recv);
|
spiExchange(spi_devices[device_desc.bus].driver, len, send, recv);
|
||||||
|
|
||||||
bus.bouncebuffer_finish(send, recv, len);
|
bus.bouncebuffer_finish(send, recv, len);
|
||||||
|
#endif
|
||||||
|
|
||||||
set_chip_select(old_cs_forced);
|
set_chip_select(old_cs_forced);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user