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