123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148 |
- #pragma once
- #include <inttypes.h>
- #include <AP_HAL/Device.h>
- class AuxiliaryBus;
- class AP_InertialSensor_Backend;
- namespace AP_HAL {
- class Semaphore;
- }
- class AuxiliaryBusSlave
- {
- friend class AuxiliaryBus;
- public:
- virtual ~AuxiliaryBusSlave();
-
- virtual int passthrough_read(uint8_t reg, uint8_t *buf, uint8_t size) = 0;
-
- virtual int passthrough_write(uint8_t reg, uint8_t val) = 0;
-
- virtual int read(uint8_t *buf) = 0;
- protected:
-
- AuxiliaryBusSlave(AuxiliaryBus &bus, uint8_t addr, uint8_t instance);
- AuxiliaryBus &_bus;
- uint8_t _addr = 0;
- uint8_t _instance = 0;
- uint8_t _sample_reg_start = 0;
- uint8_t _sample_size = 0;
- bool _registered = false;
- };
- class AuxiliaryBus
- {
- friend class AP_InertialSensor_Backend;
- public:
- AP_InertialSensor_Backend &get_backend() { return _ins_backend; }
- AuxiliaryBusSlave *request_next_slave(uint8_t addr);
- int register_periodic_read(AuxiliaryBusSlave *slave, uint8_t reg, uint8_t size);
-
- virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;
-
- virtual AP_HAL::Semaphore *get_semaphore() = 0;
-
- void set_device_type(uint8_t devtype) {
- _devid = AP_HAL::Device::change_bus_id(_devid, devtype);
- }
-
- uint32_t get_bus_id(void) const {
- return _devid;
- }
- protected:
-
- AuxiliaryBus(AP_InertialSensor_Backend &backend, uint8_t max_slaves, uint32_t devid);
- virtual ~AuxiliaryBus();
- virtual AuxiliaryBusSlave *_instantiate_slave(uint8_t addr, uint8_t instance) = 0;
- virtual int _configure_periodic_read(AuxiliaryBusSlave *slave, uint8_t reg,
- uint8_t size) = 0;
- uint8_t _n_slaves = 0;
- const uint8_t _max_slaves;
- AuxiliaryBusSlave **_slaves;
- AP_InertialSensor_Backend &_ins_backend;
- uint32_t _devid;
- };
|