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