SPIDevice.h 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148
  1. /*
  2. * This file is free software: you can redistribute it and/or modify
  3. * it under the terms of the GNU General Public License as published
  4. * by the Free Software Foundation, either version 3 of the License,
  5. * or (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. See the GNU
  10. * General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License
  13. * along with this program. If not, see <http://www.gnu.org/licenses/>.
  14. */
  15. #pragma once
  16. #include <inttypes.h>
  17. #include <AP_HAL/HAL.h>
  18. #include <AP_HAL/SPIDevice.h>
  19. #include "AP_HAL_ChibiOS.h"
  20. #if HAL_USE_SPI == TRUE
  21. #include "Semaphores.h"
  22. #include "Scheduler.h"
  23. #include "Device.h"
  24. namespace ChibiOS {
  25. class SPIBus : public DeviceBus {
  26. public:
  27. SPIBus(uint8_t bus);
  28. struct spi_dev_s *dev;
  29. uint8_t bus;
  30. SPIConfig spicfg;
  31. void dma_allocate(Shared_DMA *ctx);
  32. void dma_deallocate(Shared_DMA *ctx);
  33. bool spi_started;
  34. uint8_t slowdown;
  35. // we need an additional lock in the dma_allocate and
  36. // dma_deallocate functions to cope with 3-way contention as we
  37. // have two DMA channels that we are handling with the shared_dma
  38. // code
  39. mutex_t dma_lock;
  40. };
  41. struct SPIDesc {
  42. SPIDesc(const char *_name, uint8_t _bus,
  43. uint8_t _device, ioline_t _pal_line,
  44. uint32_t _mode, uint32_t _lowspeed, uint32_t _highspeed)
  45. : name(_name), bus(_bus), device(_device),
  46. pal_line(_pal_line), mode(_mode),
  47. lowspeed(_lowspeed), highspeed(_highspeed)
  48. {
  49. }
  50. const char *name;
  51. uint8_t bus;
  52. uint8_t device;
  53. ioline_t pal_line;
  54. uint32_t mode;
  55. uint32_t lowspeed;
  56. uint32_t highspeed;
  57. };
  58. class SPIDevice : public AP_HAL::SPIDevice {
  59. public:
  60. SPIDevice(SPIBus &_bus, SPIDesc &_device_desc);
  61. virtual ~SPIDevice();
  62. /* See AP_HAL::Device::set_speed() */
  63. bool set_speed(AP_HAL::Device::Speed speed) override;
  64. /* See AP_HAL::Device::transfer() */
  65. bool transfer(const uint8_t *send, uint32_t send_len,
  66. uint8_t *recv, uint32_t recv_len) override;
  67. /* See AP_HAL::SPIDevice::transfer_fullduplex() */
  68. bool transfer_fullduplex(const uint8_t *send, uint8_t *recv,
  69. uint32_t len) override;
  70. /*
  71. * send N bytes of clock pulses without taking CS. This is used
  72. * when initialising microSD interfaces over SPI
  73. */
  74. bool clock_pulse(uint32_t len) override;
  75. /* See AP_HAL::Device::get_semaphore() */
  76. AP_HAL::Semaphore *get_semaphore() override;
  77. /* See AP_HAL::Device::register_periodic_callback() */
  78. AP_HAL::Device::PeriodicHandle register_periodic_callback(
  79. uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
  80. /* See AP_HAL::Device::adjust_periodic_callback() */
  81. bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override;
  82. bool set_chip_select(bool set) override;
  83. bool acquire_bus(bool acquire, bool skip_cs);
  84. SPIDriver * get_driver();
  85. #ifdef HAL_SPI_CHECK_CLOCK_FREQ
  86. // used to measure clock frequencies
  87. static void test_clock_freq(void);
  88. #endif
  89. // setup a bus clock slowdown factor
  90. void set_slowdown(uint8_t slowdown) override;
  91. private:
  92. SPIBus &bus;
  93. SPIDesc &device_desc;
  94. uint32_t frequency;
  95. uint32_t freq_flag;
  96. uint32_t freq_flag_low;
  97. uint32_t freq_flag_high;
  98. char *pname;
  99. bool cs_forced;
  100. static void *spi_thread(void *arg);
  101. static uint32_t derive_freq_flag_bus(uint8_t busid, uint32_t _frequency);
  102. uint32_t derive_freq_flag(uint32_t _frequency);
  103. // low level transfer function
  104. bool do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len) WARN_IF_UNUSED;
  105. };
  106. class SPIDeviceManager : public AP_HAL::SPIDeviceManager {
  107. public:
  108. friend class SPIDevice;
  109. static SPIDeviceManager *from(AP_HAL::SPIDeviceManager *spi_mgr)
  110. {
  111. return static_cast<SPIDeviceManager*>(spi_mgr);
  112. }
  113. AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(const char *name) override;
  114. private:
  115. static SPIDesc device_table[];
  116. SPIBus *buses;
  117. };
  118. }
  119. #endif // HAL_USE_SPI