24 #if HAL_USE_SPI == TRUE 30 #define SPIDEV_MODE0 0 31 #define SPIDEV_MODE1 SPI_CR1_CPHA 32 #define SPIDEV_MODE2 SPI_CR1_CPOL 33 #define SPIDEV_MODE3 SPI_CR1_CPOL | SPI_CR1_CPHA 35 #define SPI1_CLOCK STM32_PCLK2 36 #define SPI2_CLOCK STM32_PCLK1 37 #define SPI3_CLOCK STM32_PCLK1 38 #define SPI4_CLOCK STM32_PCLK2 52 #define MHZ (1000U*1000U) 92 , device_desc(_device_desc)
144 uint8_t *recv_buf = recv;
145 const uint8_t *send_buf = send;
149 if (send ==
nullptr) {
151 }
else if (recv ==
nullptr) {
157 if (recv_buf != recv) {
158 memcpy(recv, recv_buf, len);
190 while (spi_clock_freq > _frequency && i<7) {
191 spi_clock_freq >>= 1;
198 return i * SPI_CR1_BR_0;
202 uint8_t *recv, uint32_t recv_len)
208 if ((send_len == recv_len && send == recv) || !send || !recv) {
210 do_transfer(send, recv, recv_len?recv_len:send_len);
213 uint8_t buf[send_len+recv_len];
215 memcpy(buf, send, send_len);
218 memset(&buf[send_len], 0, recv_len);
222 memcpy(recv, &buf[send_len], recv_len);
231 memcpy(buf, send, len);
233 memcpy(recv, buf, len);
310 if (strcmp(device_table[i].name, name) == 0) {
315 printf(
"SPI: Invalid device name: %s\n", name);
319 SPIDesc &desc = device_table[i];
323 for (busp = buses; busp; busp = (
SPIBus *)busp->
next) {
324 if (busp->
bus == desc.bus) {
328 if (busp ==
nullptr) {
330 busp =
new SPIBus(desc.bus);
331 if (busp ==
nullptr) {
335 busp->
bus = desc.bus;
343 #ifdef HAL_SPI_CHECK_CLOCK_FREQ 349 void SPIDevice::test_clock_freq(
void)
354 hal.
console->
printf(
"SPI1_CLOCK=%u SPI2_CLOCK=%u SPI3_CLOCK=%u SPI4_CLOCK=%u\n",
364 spicfg.cr1 = SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_BR_0;
372 hal.
console->
printf(
"SPI[%u] clock=%u\n",
spi_devices[i].busid,
unsigned(256ULL * 1000000ULL * len * 8ULL / uint64_t(t1 - t0)));
376 #endif // HAL_SPI_CHECK_CLOCK_FREQ 378 #endif // HAL_USE_SPI
int printf(const char *fmt,...)
bool clock_pulse(uint32_t len) override
void dma_deallocate(Shared_DMA *ctx)
AP_HAL::UARTDriver * console
uint32_t get_bus_id(void) const
void set_device_bus(uint8_t bus)
void bouncebuffer_setup(const uint8_t *&buf_tx, uint16_t tx_len, uint8_t *&buf_rx, uint16_t rx_len)
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
#define HAL_SEMAPHORE_BLOCK_FOREVER
static SPIDesc device_table[]
bool acquire_bus(bool acquire, bool skip_cs)
virtual void free_type(void *ptr, size_t size, Memory_Type mem_type)
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
void dma_allocate(Shared_DMA *ctx)
bool take(uint32_t timeout_ms)
static const uint32_t bus_clocks[4]
bool set_speed(AP_HAL::Device::Speed speed) override
static const struct SPIDriverInfo spi_devices[]
bool transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len) override
virtual void * malloc_type(size_t size, Memory_Type mem_type)
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device)
uint16_t derive_freq_flag(uint32_t _frequency)
#define ARRAY_SIZE_SIMPLE(_arr)
bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
AP_HAL::OwnPtr< AP_HAL::SPIDevice > get_device(const char *name)
int asprintf(char **strp, const char *fmt,...)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
void set_device_address(uint8_t address)
AP_HAL::Semaphore * get_semaphore() override
AP_HAL::Scheduler * scheduler
bool set_chip_select(bool set) override