SPIDevice.h 2.6 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283
  1. /*
  2. * Copyright (C) 2015-2016 Intel Corporation. All rights reserved.
  3. *
  4. * This file is free software: you can redistribute it and/or modify it
  5. * under the terms of the GNU General Public License as published by the
  6. * Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This file is distributed in the hope that it will be useful, but
  10. * WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  12. * See the GNU General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU General Public License along
  15. * with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. #pragma once
  18. #include <inttypes.h>
  19. #include "AP_HAL_Namespace.h"
  20. #include "Device.h"
  21. #include "utility/OwnPtr.h"
  22. namespace AP_HAL {
  23. class SPIDevice : public Device {
  24. public:
  25. SPIDevice() : Device(BUS_TYPE_SPI) { }
  26. virtual ~SPIDevice() { }
  27. /* Device implementation */
  28. /* See Device::set_speed() */
  29. virtual bool set_speed(Device::Speed speed) override = 0;
  30. /* See Device::transfer() */
  31. virtual bool transfer(const uint8_t *send, uint32_t send_len,
  32. uint8_t *recv, uint32_t recv_len) override = 0;
  33. /*
  34. * Like #transfer(), but both @send and @recv buffers are transmitted at
  35. * the same time: because of this they need to be of the same size.
  36. */
  37. virtual bool transfer_fullduplex(const uint8_t *send, uint8_t *recv,
  38. uint32_t len) = 0;
  39. /*
  40. * send N bytes of clock pulses without taking CS. This is used
  41. * when initialising microSD interfaces over SPI
  42. */
  43. virtual bool clock_pulse(uint32_t len) { return false; }
  44. /* See Device::get_semaphore() */
  45. virtual Semaphore *get_semaphore() override = 0;
  46. /* See Device::register_periodic_callback() */
  47. virtual Device::PeriodicHandle register_periodic_callback(
  48. uint32_t period_usec, Device::PeriodicCb) override = 0;
  49. /* See Device::adjust_periodic_callback() */
  50. virtual bool adjust_periodic_callback(
  51. PeriodicHandle h, uint32_t period_usec) override { return false; }
  52. // setup a bus clock slowdown factor (optional interface)
  53. virtual void set_slowdown(uint8_t slowdown) {}
  54. };
  55. class SPIDeviceManager {
  56. public:
  57. virtual OwnPtr<SPIDevice> get_device(const char *name)
  58. {
  59. return nullptr;
  60. }
  61. /* Return the number of SPI devices currently registered. */
  62. virtual uint8_t get_count() { return 0; }
  63. /* Get spi device name at @idx */
  64. virtual const char *get_device_name(uint8_t idx) { return nullptr; }
  65. };
  66. }