AuxiliaryBus.cpp 2.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101
  1. #include <assert.h>
  2. #include <stdlib.h>
  3. #include "AuxiliaryBus.h"
  4. AuxiliaryBusSlave::AuxiliaryBusSlave(AuxiliaryBus &bus, uint8_t addr,
  5. uint8_t instance)
  6. : _bus(bus)
  7. , _addr(addr)
  8. , _instance(instance)
  9. {
  10. }
  11. AuxiliaryBusSlave::~AuxiliaryBusSlave()
  12. {
  13. }
  14. AuxiliaryBus::AuxiliaryBus(AP_InertialSensor_Backend &backend, uint8_t max_slaves, uint32_t devid)
  15. : _max_slaves(max_slaves)
  16. , _ins_backend(backend)
  17. , _devid(devid)
  18. {
  19. _slaves = (AuxiliaryBusSlave**) calloc(max_slaves, sizeof(AuxiliaryBusSlave*));
  20. }
  21. AuxiliaryBus::~AuxiliaryBus()
  22. {
  23. for (int i = _n_slaves - 1; i >= 0; i--) {
  24. delete _slaves[i];
  25. }
  26. free(_slaves);
  27. }
  28. /*
  29. * Get the next available slave for the sensor exposing this AuxiliaryBus.
  30. * If a new slave cannot be registered or instantiated, `nullptr` is returned.
  31. * Otherwise a new slave is returned, but it's not registered (and therefore
  32. * not owned by the AuxiliaryBus).
  33. *
  34. * After using the slave, if it's not registered for a periodic read it must
  35. * be destroyed.
  36. *
  37. * @addr: the address of this slave in the bus
  38. *
  39. * Return a new slave if successful or `nullptr` otherwise.
  40. */
  41. AuxiliaryBusSlave *AuxiliaryBus::request_next_slave(uint8_t addr)
  42. {
  43. if (_n_slaves == _max_slaves)
  44. return nullptr;
  45. AuxiliaryBusSlave *slave = _instantiate_slave(addr, _n_slaves);
  46. if (!slave)
  47. return nullptr;
  48. return slave;
  49. }
  50. /*
  51. * Register a periodic read. This should be called after the slave sensor is
  52. * already configured and the only thing the master needs to do is to copy a
  53. * set of registers from the slave to its own registers.
  54. *
  55. * The sample rate is hard-coded, depending on the sensor that exports this
  56. * AuxiliaryBus.
  57. *
  58. * After this call the AuxiliaryBusSlave is owned by this object and should
  59. * not be destroyed. A typical call chain to use a sensor in an AuxiliaryBus
  60. * is (error checking omitted for brevity):
  61. *
  62. * AuxiliaryBusSlave *slave = bus->request_next_slave(addr);
  63. * slave->passthrough_read(WHO_AM_I, buf, 1);
  64. * slave->passthrough_write(...);
  65. * slave->passthrough_write(...);
  66. * ...
  67. * bus->register_periodic_read(slave, SAMPLE_START_REG, SAMPLE_SIZE);
  68. *
  69. * @slave: the AuxiliaryBusSlave already configured to be in continuous mode
  70. * @reg: the first register of the block to use in each periodic transfer
  71. * @size: the block size, usually the size of the sample multiplied by the
  72. * number of axes in each sample.
  73. *
  74. * Return 0 on success or < 0 on error.
  75. */
  76. int AuxiliaryBus::register_periodic_read(AuxiliaryBusSlave *slave, uint8_t reg,
  77. uint8_t size)
  78. {
  79. assert(slave->_instance == _n_slaves);
  80. assert(_n_slaves < _max_slaves);
  81. int r = _configure_periodic_read(slave, reg, size);
  82. if (r < 0)
  83. return r;
  84. slave->_sample_reg_start = reg;
  85. slave->_sample_size = size;
  86. slave->_registered = true;
  87. _slaves[_n_slaves++] = slave;
  88. return 0;
  89. }