AuxiliaryBus.h 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148
  1. /*
  2. * Copyright (C) 2015 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/Device.h>
  20. class AuxiliaryBus;
  21. class AP_InertialSensor_Backend;
  22. namespace AP_HAL {
  23. class Semaphore;
  24. }
  25. class AuxiliaryBusSlave
  26. {
  27. friend class AuxiliaryBus;
  28. public:
  29. virtual ~AuxiliaryBusSlave();
  30. /*
  31. * Read a block of registers from the slave. This is a one-time read. Must
  32. * be implemented by the sensor exposing the AuxiliaryBus.
  33. *
  34. * This method cannot be called after the periodic read is configured
  35. * since the registers for the periodic read may be shared with the
  36. * passthrough reads.
  37. *
  38. * @reg: the first register of the block to use in this one time transfer
  39. * @buf: buffer in which to write the values read
  40. * @size: the buffer size
  41. *
  42. * Return the number of bytes read on success or < 0 on error
  43. */
  44. virtual int passthrough_read(uint8_t reg, uint8_t *buf, uint8_t size) = 0;
  45. /*
  46. * Write a single value into a register of this slave. Must be implemented
  47. * by the sensor exposing the AuxiliaryBus.
  48. *
  49. * This method cannot be called after the periodic read is configured
  50. * since the registers for the periodic read may be shared with the
  51. * passthrough writes.
  52. *
  53. * @reg: the register to use in this one time transfer
  54. * @val: the value to write
  55. *
  56. * Return the number of bytes written on success or < 0 on error
  57. */
  58. virtual int passthrough_write(uint8_t reg, uint8_t val) = 0;
  59. /*
  60. * Read the block of registers that were read from the slave on the last
  61. * time a periodic read occurred.
  62. *
  63. * This method must be called after the periodic read is configured and
  64. * the buffer must be large enough to accommodate the size configured.
  65. *
  66. * @buf: buffer in which to write the values read
  67. *
  68. * Return the number of bytes read on success or < 0 on error
  69. */
  70. virtual int read(uint8_t *buf) = 0;
  71. protected:
  72. /* Only AuxiliaryBus is able to create a slave */
  73. AuxiliaryBusSlave(AuxiliaryBus &bus, uint8_t addr, uint8_t instance);
  74. AuxiliaryBus &_bus;
  75. uint8_t _addr = 0;
  76. uint8_t _instance = 0;
  77. uint8_t _sample_reg_start = 0;
  78. uint8_t _sample_size = 0;
  79. bool _registered = false;
  80. };
  81. class AuxiliaryBus
  82. {
  83. friend class AP_InertialSensor_Backend;
  84. public:
  85. AP_InertialSensor_Backend &get_backend() { return _ins_backend; }
  86. AuxiliaryBusSlave *request_next_slave(uint8_t addr);
  87. int register_periodic_read(AuxiliaryBusSlave *slave, uint8_t reg, uint8_t size);
  88. /* See AP_HAL::Device::register_periodic_callback()
  89. *
  90. * This method must be implemented by the sensor exposing the
  91. * AuxiliaryBus.
  92. */
  93. virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;
  94. /*
  95. * Get the semaphore needed to call methods on the bus this sensor is on.
  96. * Internally no locks are taken and it's the caller's duty to lock and
  97. * unlock the bus as needed.
  98. *
  99. * This method must be implemented by the sensor exposing the
  100. * AuxiliaryBus.
  101. *
  102. * Return the semaphore used protect transfers on the bus
  103. */
  104. virtual AP_HAL::Semaphore *get_semaphore() = 0;
  105. // set device type within a device class
  106. void set_device_type(uint8_t devtype) {
  107. _devid = AP_HAL::Device::change_bus_id(_devid, devtype);
  108. }
  109. // return 24 bit bus identifier
  110. uint32_t get_bus_id(void) const {
  111. return _devid;
  112. }
  113. protected:
  114. /* Only AP_InertialSensor_Backend is able to create a bus */
  115. AuxiliaryBus(AP_InertialSensor_Backend &backend, uint8_t max_slaves, uint32_t devid);
  116. virtual ~AuxiliaryBus();
  117. virtual AuxiliaryBusSlave *_instantiate_slave(uint8_t addr, uint8_t instance) = 0;
  118. virtual int _configure_periodic_read(AuxiliaryBusSlave *slave, uint8_t reg,
  119. uint8_t size) = 0;
  120. uint8_t _n_slaves = 0;
  121. const uint8_t _max_slaves;
  122. AuxiliaryBusSlave **_slaves;
  123. AP_InertialSensor_Backend &_ins_backend;
  124. uint32_t _devid;
  125. };