Device.h 9.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310
  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 "utility/functor.h"
  21. /*
  22. * This is an interface abstracting I2C and SPI devices
  23. */
  24. class AP_HAL::Device {
  25. public:
  26. enum BusType {
  27. BUS_TYPE_UNKNOWN = 0,
  28. BUS_TYPE_I2C = 1,
  29. BUS_TYPE_SPI = 2,
  30. BUS_TYPE_UAVCAN = 3,
  31. BUS_TYPE_SITL = 4
  32. };
  33. enum Speed {
  34. SPEED_HIGH,
  35. SPEED_LOW,
  36. };
  37. FUNCTOR_TYPEDEF(PeriodicCb, void);
  38. typedef void* PeriodicHandle;
  39. Device(enum BusType type)
  40. {
  41. _bus_id.devid_s.bus_type = type;
  42. }
  43. // return bus type
  44. enum BusType bus_type(void) const {
  45. return _bus_id.devid_s.bus_type;
  46. }
  47. // return bus number
  48. uint8_t bus_num(void) const {
  49. return _bus_id.devid_s.bus;
  50. }
  51. // return 24 bit bus identifier
  52. uint32_t get_bus_id(void) const {
  53. return _bus_id.devid;
  54. }
  55. // return address on bus
  56. uint8_t get_bus_address(void) const {
  57. return _bus_id.devid_s.address;
  58. }
  59. // set device type within a device class (eg. AP_COMPASS_TYPE_LSM303D)
  60. void set_device_type(uint8_t devtype) {
  61. _bus_id.devid_s.devtype = devtype;
  62. }
  63. virtual ~Device() {
  64. if (_checked.regs != nullptr) {
  65. delete[] _checked.regs;
  66. }
  67. }
  68. /*
  69. * Change device address. Note that this is the 7 bit address, it
  70. * does not include the bit for read/write. Only works on I2C
  71. */
  72. virtual void set_address(uint8_t address) {};
  73. /*
  74. * Set the speed of future transfers. Depending on the bus the speed may
  75. * be shared for all devices on the same bus.
  76. *
  77. * Return: true if speed was successfully set or platform doesn't implement
  78. * it; false otherwise.
  79. */
  80. virtual bool set_speed(Speed speed) = 0;
  81. /*
  82. * Core transfer function. This does a single bus transaction which
  83. * sends send_len bytes and receives recv_len bytes back from the slave.
  84. *
  85. * Return: true on a successful transfer, false on failure.
  86. */
  87. virtual bool transfer(const uint8_t *send, uint32_t send_len,
  88. uint8_t *recv, uint32_t recv_len) = 0;
  89. /**
  90. * Wrapper function over #transfer() to read recv_len registers, starting
  91. * by first_reg, into the array pointed by recv. The read flag passed to
  92. * #set_read_flag(uint8_t) is ORed with first_reg before performing the
  93. * transfer.
  94. *
  95. * Return: true on a successful transfer, false on failure.
  96. */
  97. bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
  98. {
  99. first_reg |= _read_flag;
  100. return transfer(&first_reg, 1, recv, recv_len);
  101. }
  102. /**
  103. * Wrapper function over #transfer() to write a byte to the register reg.
  104. * The transfer is done by sending reg and val in that order.
  105. *
  106. * Return: true on a successful transfer, false on failure.
  107. */
  108. bool write_register(uint8_t reg, uint8_t val, bool checked=false)
  109. {
  110. uint8_t buf[2] = { reg, val };
  111. if (checked) {
  112. set_checked_register(reg, val);
  113. }
  114. return transfer(buf, sizeof(buf), nullptr, 0);
  115. }
  116. /**
  117. * set a value for a checked register
  118. */
  119. void set_checked_register(uint8_t reg, uint8_t val);
  120. /**
  121. * setup for register value checking. Frequency is how often to check registers. If set to 10 then
  122. * every 10th call to check_next_register will check a register
  123. */
  124. bool setup_checked_registers(uint8_t num_regs, uint8_t frequency=10);
  125. /**
  126. * check next register value for correctness. Return false if value is incorrect
  127. * or register checking has not been setup
  128. */
  129. bool check_next_register(void);
  130. /**
  131. * Wrapper function over #transfer() to read a sequence of bytes from
  132. * device. No value is written, differently from the #read_registers()
  133. * method and hence doesn't include the read flag set by #set_read_flag()
  134. */
  135. bool read(uint8_t *recv, uint32_t recv_len)
  136. {
  137. return transfer(nullptr, 0, recv, recv_len);
  138. }
  139. /*
  140. * Get the semaphore for the bus this device is in. This is intended for
  141. * drivers to use during initialization phase only.
  142. */
  143. virtual AP_HAL::Semaphore *get_semaphore() = 0;
  144. /*
  145. * Register a periodic callback for this bus. All callbacks on the
  146. * same bus are made from the same thread with lock already taken. In
  147. * other words, the callback is not executed on the main thread (or the
  148. * thread which registered the callback), but in a separate per-bus
  149. * thread.
  150. *
  151. * After registering the periodic callback, the other functions should not
  152. * be used anymore from other contexts. If it really needs to be done, the
  153. * lock must be taken.
  154. *
  155. * Return: A handle for this periodic callback. To cancel the callback
  156. * call #unregister_callback() or return false on the callback.
  157. */
  158. virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb) = 0;
  159. /*
  160. * Adjust the time for the periodic callback registered with
  161. * #register_periodic_callback. Note that the time will be re-calculated
  162. * from the moment this call is made and expire after @period_usec.
  163. *
  164. * Return: true if periodic callback was successfully adjusted, false otherwise.
  165. */
  166. virtual bool adjust_periodic_callback(PeriodicHandle h, uint32_t period_usec) = 0;
  167. /*
  168. * Cancel a periodic callback on this bus.
  169. *
  170. * Return: true if callback was successfully unregistered, false
  171. * otherwise.
  172. */
  173. virtual bool unregister_callback(PeriodicHandle h) { return false; }
  174. /*
  175. allows to set callback that will be called after DMA transfer complete.
  176. if this callback is set then any read/write operation will return directly after transfer setup and
  177. bus semaphore must not be released until register_completion_callback(0) called from callback itself
  178. */
  179. virtual void register_completion_callback(AP_HAL::MemberProc proc) {}
  180. virtual void register_completion_callback(AP_HAL::Proc proc) {}
  181. /*
  182. * support for direct control of SPI chip select. Needed for
  183. * devices with unusual SPI transfer patterns that include
  184. * specific delays
  185. */
  186. virtual bool set_chip_select(bool set) { return false; }
  187. /**
  188. * Some devices connected on the I2C or SPI bus require a bit to be set on
  189. * the register address in order to perform a read operation. This sets a
  190. * flag to be used by #read_registers(). The flag's default value is zero.
  191. */
  192. void set_read_flag(uint8_t flag)
  193. {
  194. _read_flag = flag;
  195. }
  196. /**
  197. * make a bus id given bus type, bus number, bus address and
  198. * device type This is for use by devices that do not use one of
  199. * the standard HAL Device types, such as UAVCAN devices
  200. */
  201. static uint32_t make_bus_id(enum BusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype) {
  202. union DeviceId d {};
  203. d.devid_s.bus_type = bus_type;
  204. d.devid_s.bus = bus;
  205. d.devid_s.address = address;
  206. d.devid_s.devtype = devtype;
  207. return d.devid;
  208. }
  209. /**
  210. * return a new bus ID for the same bus connection but a new device type.
  211. * This is used for auxillary bus connections
  212. */
  213. static uint32_t change_bus_id(uint32_t old_id, uint8_t devtype) {
  214. union DeviceId d;
  215. d.devid = old_id;
  216. d.devid_s.devtype = devtype;
  217. return d.devid;
  218. }
  219. /**
  220. * return bus ID with a new devtype
  221. */
  222. uint32_t get_bus_id_devtype(uint8_t devtype) {
  223. return change_bus_id(get_bus_id(), devtype);
  224. }
  225. /* set number of retries on transfers */
  226. virtual void set_retries(uint8_t retries) {};
  227. protected:
  228. uint8_t _read_flag = 0;
  229. /*
  230. broken out device elements. The bitfields are used to keep
  231. the overall value small enough to fit in a float accurately,
  232. which makes it possible to transport over the MAVLink
  233. parameter protocol without loss of information.
  234. */
  235. struct DeviceStructure {
  236. enum BusType bus_type : 3;
  237. uint8_t bus: 5; // which instance of the bus type
  238. uint8_t address; // address on the bus (eg. I2C address)
  239. uint8_t devtype; // device class specific device type
  240. };
  241. union DeviceId {
  242. struct DeviceStructure devid_s;
  243. uint32_t devid;
  244. };
  245. union DeviceId _bus_id;
  246. // set device address (eg. i2c bus address or spi CS)
  247. void set_device_address(uint8_t address) {
  248. _bus_id.devid_s.address = address;
  249. }
  250. // set device bus number
  251. void set_device_bus(uint8_t bus) {
  252. _bus_id.devid_s.bus = bus;
  253. }
  254. private:
  255. // checked registers
  256. struct checkreg {
  257. uint8_t regnum;
  258. uint8_t value;
  259. };
  260. struct {
  261. uint8_t n_allocated;
  262. uint8_t n_set;
  263. uint8_t next;
  264. uint8_t frequency;
  265. uint8_t counter;
  266. struct checkreg *regs;
  267. } _checked;
  268. };