SPIDevice.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475
  1. /*
  2. * This file is free software: you can redistribute it and/or modify it
  3. * under the terms of the GNU General Public License as published by the
  4. * Free Software Foundation, either version 3 of the License, or
  5. * (at your option) any later version.
  6. *
  7. * This file is distributed in the hope that it will be useful, but
  8. * WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  10. * See the GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License along
  13. * with this program. If not, see <http://www.gnu.org/licenses/>.
  14. */
  15. #include "SPIDevice.h"
  16. #include <AP_HAL/AP_HAL.h>
  17. #include <AP_Math/AP_Math.h>
  18. #include <AP_HAL/utility/OwnPtr.h>
  19. #include <AP_InternalError/AP_InternalError.h>
  20. #include "Util.h"
  21. #include "Scheduler.h"
  22. #include "Semaphores.h"
  23. #include <stdio.h>
  24. #include "hwdef/common/stm32_util.h"
  25. #if HAL_USE_SPI == TRUE
  26. using namespace ChibiOS;
  27. extern const AP_HAL::HAL& hal;
  28. // SPI mode numbers
  29. #if defined(STM32H7)
  30. #define SPIDEV_MODE0 0
  31. #define SPIDEV_MODE1 SPI_CFG2_CPHA
  32. #define SPIDEV_MODE2 SPI_CFG2_CPOL
  33. #define SPIDEV_MODE3 SPI_CFG2_CPOL | SPI_CFG2_CPHA
  34. #define SPI1_CLOCK STM32_SPI1CLK
  35. #define SPI2_CLOCK STM32_SPI2CLK
  36. #define SPI3_CLOCK STM32_SPI3CLK
  37. #define SPI4_CLOCK STM32_SPI4CLK
  38. #define SPI5_CLOCK STM32_SPI5CLK
  39. #define SPI6_CLOCK STM32_SPI6CLK
  40. #else // F4 and F7
  41. #define SPIDEV_MODE0 0
  42. #define SPIDEV_MODE1 SPI_CR1_CPHA
  43. #define SPIDEV_MODE2 SPI_CR1_CPOL
  44. #define SPIDEV_MODE3 SPI_CR1_CPOL | SPI_CR1_CPHA
  45. #define SPI1_CLOCK STM32_PCLK2
  46. #define SPI2_CLOCK STM32_PCLK1
  47. #define SPI3_CLOCK STM32_PCLK1
  48. #define SPI4_CLOCK STM32_PCLK2
  49. #define SPI5_CLOCK STM32_PCLK2
  50. #define SPI6_CLOCK STM32_PCLK2
  51. #endif
  52. // expected bus clock speeds
  53. static const uint32_t bus_clocks[6] = {
  54. SPI1_CLOCK, SPI2_CLOCK, SPI3_CLOCK, SPI4_CLOCK, SPI5_CLOCK, SPI6_CLOCK
  55. };
  56. static const struct SPIDriverInfo {
  57. SPIDriver *driver;
  58. uint8_t busid; // used for device IDs in parameters
  59. uint8_t dma_channel_rx;
  60. uint8_t dma_channel_tx;
  61. } spi_devices[] = { HAL_SPI_BUS_LIST };
  62. #define MHZ (1000U*1000U)
  63. #define KHZ (1000U)
  64. // device list comes from hwdef.dat
  65. ChibiOS::SPIDesc SPIDeviceManager::device_table[] = { HAL_SPI_DEVICE_LIST };
  66. SPIBus::SPIBus(uint8_t _bus) :
  67. DeviceBus(APM_SPI_PRIORITY),
  68. bus(_bus)
  69. {
  70. chMtxObjectInit(&dma_lock);
  71. // allow for sharing of DMA channels with other peripherals
  72. dma_handle = new Shared_DMA(spi_devices[bus].dma_channel_rx,
  73. spi_devices[bus].dma_channel_tx,
  74. FUNCTOR_BIND_MEMBER(&SPIBus::dma_allocate, void, Shared_DMA *),
  75. FUNCTOR_BIND_MEMBER(&SPIBus::dma_deallocate, void, Shared_DMA *));
  76. }
  77. /*
  78. allocate DMA channel
  79. */
  80. void SPIBus::dma_allocate(Shared_DMA *ctx)
  81. {
  82. // nothing to do as we call spiStart() on each transaction
  83. }
  84. /*
  85. deallocate DMA channel
  86. */
  87. void SPIBus::dma_deallocate(Shared_DMA *ctx)
  88. {
  89. chMtxLock(&dma_lock);
  90. // another non-SPI peripheral wants one of our DMA channels
  91. if (spi_started) {
  92. spiStop(spi_devices[bus].driver);
  93. spi_started = false;
  94. }
  95. chMtxUnlock(&dma_lock);
  96. }
  97. SPIDevice::SPIDevice(SPIBus &_bus, SPIDesc &_device_desc)
  98. : bus(_bus)
  99. , device_desc(_device_desc)
  100. {
  101. set_device_bus(spi_devices[_bus.bus].busid);
  102. set_device_address(_device_desc.device);
  103. freq_flag_low = derive_freq_flag(device_desc.lowspeed);
  104. freq_flag_high = derive_freq_flag(device_desc.highspeed);
  105. set_speed(AP_HAL::Device::SPEED_LOW);
  106. asprintf(&pname, "SPI:%s:%u:%u",
  107. device_desc.name,
  108. (unsigned)bus.bus, (unsigned)device_desc.device);
  109. //printf("SPI device %s on %u:%u at speed %u mode %u\n",
  110. // device_desc.name,
  111. // (unsigned)bus.bus, (unsigned)device_desc.device,
  112. // (unsigned)frequency, (unsigned)device_desc.mode);
  113. }
  114. SPIDevice::~SPIDevice()
  115. {
  116. //printf("SPI device %s on %u:%u closed\n", device_desc.name,
  117. // (unsigned)bus.bus, (unsigned)device_desc.device);
  118. free(pname);
  119. }
  120. SPIDriver * SPIDevice::get_driver() {
  121. return spi_devices[device_desc.bus].driver;
  122. }
  123. bool SPIDevice::set_speed(AP_HAL::Device::Speed speed)
  124. {
  125. switch (speed) {
  126. case AP_HAL::Device::SPEED_HIGH:
  127. freq_flag = freq_flag_high;
  128. break;
  129. case AP_HAL::Device::SPEED_LOW:
  130. freq_flag = freq_flag_low;
  131. break;
  132. }
  133. return true;
  134. }
  135. /*
  136. setup a bus slowdown factor for high speed mode
  137. */
  138. void SPIDevice::set_slowdown(uint8_t slowdown)
  139. {
  140. slowdown = constrain_int16(slowdown+1, 1, 32);
  141. freq_flag_high = derive_freq_flag(device_desc.highspeed / slowdown);
  142. }
  143. /*
  144. low level transfer function
  145. */
  146. bool SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
  147. {
  148. bool old_cs_forced = cs_forced;
  149. if (!set_chip_select(true)) {
  150. return false;
  151. }
  152. bool ret = true;
  153. #if defined(HAL_SPI_USE_POLLED)
  154. for (uint16_t i=0; i<len; i++) {
  155. uint8_t ret = spiPolledExchange(spi_devices[device_desc.bus].driver, send?send[i]:0);
  156. if (recv) {
  157. recv[i] = ret;
  158. }
  159. }
  160. #else
  161. bus.bouncebuffer_setup(send, len, recv, len);
  162. osalSysLock();
  163. hal.util->persistent_data.spi_count++;
  164. if (send == nullptr) {
  165. spiStartReceiveI(spi_devices[device_desc.bus].driver, len, recv);
  166. } else if (recv == nullptr) {
  167. spiStartSendI(spi_devices[device_desc.bus].driver, len, send);
  168. } else {
  169. spiStartExchangeI(spi_devices[device_desc.bus].driver, len, send, recv);
  170. }
  171. // we allow SPI transfers to take a maximum of 20ms plus 32us per
  172. // byte. This covers all use cases in ArduPilot. We don't ever
  173. // expect this timeout to trigger unless there is a severe MCU
  174. // error
  175. const uint32_t timeout_us = 20000U + len * 32U;
  176. msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->thread, TIME_MS2I(timeout_us));
  177. osalSysUnlock();
  178. if (msg == MSG_TIMEOUT) {
  179. ret = false;
  180. AP::internalerror().error(AP_InternalError::error_t::spi_fail);
  181. spiAbort(spi_devices[device_desc.bus].driver);
  182. }
  183. bus.bouncebuffer_finish(send, recv, len);
  184. #endif
  185. set_chip_select(old_cs_forced);
  186. return ret;
  187. }
  188. bool SPIDevice::clock_pulse(uint32_t n)
  189. {
  190. if (!cs_forced) {
  191. //special mode to init sdcard without cs asserted
  192. bus.semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER);
  193. acquire_bus(true, true);
  194. spiIgnore(spi_devices[device_desc.bus].driver, n);
  195. acquire_bus(false, true);
  196. bus.semaphore.give();
  197. } else {
  198. bus.semaphore.assert_owner();
  199. spiIgnore(spi_devices[device_desc.bus].driver, n);
  200. }
  201. return true;
  202. }
  203. uint32_t SPIDevice::derive_freq_flag_bus(uint8_t busid, uint32_t _frequency)
  204. {
  205. uint32_t spi_clock_freq = SPI1_CLOCK;
  206. if (busid > 0 && uint8_t(busid-1) < ARRAY_SIZE(bus_clocks)) {
  207. spi_clock_freq = bus_clocks[busid-1] / 2;
  208. }
  209. // find first divisor that brings us below the desired SPI clock
  210. uint32_t i = 0;
  211. while (spi_clock_freq > _frequency && i<7) {
  212. spi_clock_freq >>= 1;
  213. i++;
  214. }
  215. // assuming the bitrate bits are consecutive in the CR1 register,
  216. // we can just multiply by BR_0 to get the right bits for the desired
  217. // scaling
  218. #if defined(STM32H7)
  219. return (i * SPI_CFG1_MBR_0) | SPI_CFG1_DSIZE_VALUE(7); // 8 bit transfers
  220. #else
  221. return i * SPI_CR1_BR_0;
  222. #endif
  223. }
  224. uint32_t SPIDevice::derive_freq_flag(uint32_t _frequency)
  225. {
  226. uint8_t busid = spi_devices[device_desc.bus].busid;
  227. return derive_freq_flag_bus(busid, _frequency);
  228. }
  229. bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
  230. uint8_t *recv, uint32_t recv_len)
  231. {
  232. if (!bus.semaphore.check_owner()) {
  233. hal.console->printf("SPI: not owner of 0x%x\n", unsigned(get_bus_id()));
  234. return false;
  235. }
  236. if ((send_len == recv_len && send == recv) || !send || !recv) {
  237. // simplest cases, needed for DMA
  238. return do_transfer(send, recv, recv_len?recv_len:send_len);
  239. }
  240. uint8_t buf[send_len+recv_len];
  241. if (send_len > 0) {
  242. memcpy(buf, send, send_len);
  243. }
  244. if (recv_len > 0) {
  245. memset(&buf[send_len], 0, recv_len);
  246. }
  247. bool ret = do_transfer(buf, buf, send_len+recv_len);
  248. if (ret && recv_len > 0) {
  249. memcpy(recv, &buf[send_len], recv_len);
  250. }
  251. return ret;
  252. }
  253. bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len)
  254. {
  255. bus.semaphore.assert_owner();
  256. uint8_t buf[len];
  257. memcpy(buf, send, len);
  258. bool ret = do_transfer(buf, buf, len);
  259. if (ret) {
  260. memcpy(recv, buf, len);
  261. }
  262. return ret;
  263. }
  264. AP_HAL::Semaphore *SPIDevice::get_semaphore()
  265. {
  266. return &bus.semaphore;
  267. }
  268. AP_HAL::Device::PeriodicHandle SPIDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
  269. {
  270. return bus.register_periodic_callback(period_usec, cb, this);
  271. }
  272. bool SPIDevice::adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
  273. {
  274. return bus.adjust_timer(h, period_usec);
  275. }
  276. /*
  277. used to acquire bus and (optionally) assert cs
  278. */
  279. bool SPIDevice::acquire_bus(bool set, bool skip_cs)
  280. {
  281. bus.semaphore.assert_owner();
  282. if (set && cs_forced) {
  283. return true;
  284. }
  285. if (!set && !cs_forced) {
  286. return false;
  287. }
  288. if (!set && cs_forced) {
  289. if(!skip_cs) {
  290. spiUnselectI(spi_devices[device_desc.bus].driver); /* Slave Select de-assertion. */
  291. }
  292. spiReleaseBus(spi_devices[device_desc.bus].driver); /* Ownership release. */
  293. cs_forced = false;
  294. bus.dma_handle->unlock();
  295. } else {
  296. bus.dma_handle->lock();
  297. spiAcquireBus(spi_devices[device_desc.bus].driver); /* Acquire ownership of the bus. */
  298. bus.spicfg.end_cb = nullptr;
  299. bus.spicfg.ssport = PAL_PORT(device_desc.pal_line);
  300. bus.spicfg.sspad = PAL_PAD(device_desc.pal_line);
  301. #if defined(STM32H7)
  302. bus.spicfg.cfg1 = freq_flag;
  303. bus.spicfg.cfg2 = device_desc.mode;
  304. if (bus.spicfg.dummytx == nullptr) {
  305. bus.spicfg.dummytx = (uint32_t *)malloc_dma(4);
  306. memset(bus.spicfg.dummytx, 0xFF, 4);
  307. }
  308. if (bus.spicfg.dummyrx == nullptr) {
  309. bus.spicfg.dummyrx = (uint32_t *)malloc_dma(4);
  310. }
  311. #else
  312. bus.spicfg.cr1 = (uint16_t)(freq_flag | device_desc.mode);
  313. bus.spicfg.cr2 = 0;
  314. #endif
  315. if (bus.spi_started) {
  316. spiStop(spi_devices[device_desc.bus].driver);
  317. bus.spi_started = false;
  318. }
  319. spiStart(spi_devices[device_desc.bus].driver, &bus.spicfg); /* Setup transfer parameters. */
  320. bus.spi_started = true;
  321. if(!skip_cs) {
  322. spiSelectI(spi_devices[device_desc.bus].driver); /* Slave Select assertion. */
  323. }
  324. cs_forced = true;
  325. }
  326. return true;
  327. }
  328. /*
  329. allow for control of SPI chip select pin
  330. */
  331. bool SPIDevice::set_chip_select(bool set) {
  332. return acquire_bus(set, false);
  333. }
  334. /*
  335. return a SPIDevice given a string device name
  336. */
  337. AP_HAL::OwnPtr<AP_HAL::SPIDevice>
  338. SPIDeviceManager::get_device(const char *name)
  339. {
  340. /* Find the bus description in the table */
  341. uint8_t i;
  342. for (i = 0; i<ARRAY_SIZE(device_table); i++) {
  343. if (strcmp(device_table[i].name, name) == 0) {
  344. break;
  345. }
  346. }
  347. if (i == ARRAY_SIZE(device_table)) {
  348. return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(nullptr);
  349. }
  350. SPIDesc &desc = device_table[i];
  351. // find the bus
  352. SPIBus *busp;
  353. for (busp = buses; busp; busp = (SPIBus *)busp->next) {
  354. if (busp->bus == desc.bus) {
  355. break;
  356. }
  357. }
  358. if (busp == nullptr) {
  359. // create a new one
  360. busp = new SPIBus(desc.bus);
  361. if (busp == nullptr) {
  362. return nullptr;
  363. }
  364. busp->next = buses;
  365. busp->bus = desc.bus;
  366. buses = busp;
  367. }
  368. return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(new SPIDevice(*busp, desc));
  369. }
  370. #ifdef HAL_SPI_CHECK_CLOCK_FREQ
  371. /*
  372. test clock frequencies. This measures the actual SPI clock
  373. frequencies on all configured SPI buses. Used during board bringup
  374. to validate clock configuration
  375. */
  376. void SPIDevice::test_clock_freq(void)
  377. {
  378. // delay for USB to come up
  379. hal.console->printf("Waiting for USB\n");
  380. for (uint8_t i=0; i<3; i++) {
  381. hal.scheduler->delay(1000);
  382. hal.console->printf("Waiting %u\n", AP_HAL::millis());
  383. }
  384. hal.console->printf("CLOCKS=\n");
  385. for (uint8_t i=0; i<ARRAY_SIZE(bus_clocks); i++) {
  386. hal.console->printf("%u:%u ", i+1, bus_clocks[i]);
  387. }
  388. hal.console->printf("\n");
  389. // we will send 1024 bytes without any CS asserted and measure the
  390. // time it takes to do the transfer
  391. uint16_t len = 1024;
  392. uint8_t *buf1 = (uint8_t *)hal.util->malloc_type(len, AP_HAL::Util::MEM_DMA_SAFE);
  393. uint8_t *buf2 = (uint8_t *)hal.util->malloc_type(len, AP_HAL::Util::MEM_DMA_SAFE);
  394. for (uint8_t i=0; i<ARRAY_SIZE(spi_devices); i++) {
  395. SPIConfig spicfg {};
  396. const uint32_t target_freq = 2000000UL;
  397. // use a clock divisor of 256 for maximum resolution
  398. #if defined(STM32H7)
  399. spicfg.cfg1 = derive_freq_flag_bus(spi_devices[i].busid, target_freq);
  400. #else
  401. spicfg.cr1 = derive_freq_flag_bus(spi_devices[i].busid, target_freq);
  402. #endif
  403. spiAcquireBus(spi_devices[i].driver);
  404. spiStart(spi_devices[i].driver, &spicfg);
  405. uint32_t t0 = AP_HAL::micros();
  406. spiStartExchange(spi_devices[i].driver, len, buf1, buf2);
  407. chSysLock();
  408. msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[i].driver->thread, TIME_MS2I(100));
  409. chSysUnlock();
  410. if (msg == MSG_TIMEOUT) {
  411. spiAbort(spi_devices[i].driver);
  412. hal.console->printf("SPI[%u] FAIL %p %p\n", spi_devices[i].busid, buf1, buf2);
  413. spiStop(spi_devices[i].driver);
  414. spiReleaseBus(spi_devices[i].driver);
  415. continue;
  416. }
  417. uint32_t t1 = AP_HAL::micros();
  418. spiStop(spi_devices[i].driver);
  419. spiReleaseBus(spi_devices[i].driver);
  420. hal.console->printf("SPI[%u] clock=%u\n", spi_devices[i].busid, unsigned(1000000ULL * len * 8ULL / uint64_t(t1 - t0)));
  421. }
  422. hal.util->free_type(buf1, len, AP_HAL::Util::MEM_DMA_SAFE);
  423. hal.util->free_type(buf2, len, AP_HAL::Util::MEM_DMA_SAFE);
  424. }
  425. #endif // HAL_SPI_CHECK_CLOCK_FREQ
  426. #endif // HAL_USE_SPI