73 virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;
74 virtual bool register_read(uint8_t reg, uint8_t *val) = 0;
75 virtual bool register_write(uint8_t reg, uint8_t val) = 0;
84 virtual void set_device_type(uint8_t devtype) = 0;
87 virtual uint32_t get_bus_id(
void)
const = 0;
95 virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size)
override;
96 virtual bool register_read(uint8_t reg, uint8_t *val)
override;
97 virtual bool register_write(uint8_t reg, uint8_t val)
override;
104 _dev->set_device_type(devtype);
109 return _dev->get_bus_id();
120 uint8_t backend_instance, uint8_t addr);
123 bool block_read(uint8_t reg, uint8_t *buf, uint32_t size)
override;
124 bool register_read(uint8_t reg, uint8_t *val)
override;
125 bool register_write(uint8_t reg, uint8_t val)
override;
132 bool start_measurements();
135 void set_device_type(uint8_t devtype)
override;
138 uint32_t get_bus_id(
void)
const override;
static constexpr const char * name
float _magnetometer_ASA[3]
AuxiliaryBusSlave * _slave
static AP_InertialSensor ins
virtual ~AP_AK8963_BusDriver()
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
void _make_factory_sensitivity_adjustment(Vector3f &field) const
void set_device_type(uint8_t devtype) override
static AP_Compass_Backend * probe_mpu9250(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
AP_Compass_AK8963(Compass &compass, AP_AK8963_BusDriver *bus, enum Rotation rotation=ROTATION_NONE)
Common definitions and utility routines for the ArduPilot libraries.
void _make_adc_sensitivity_adjustment(Vector3f &field) const
virtual ~AP_Compass_AK8963()
uint32_t get_bus_id(void) const override
AP_AK8963_BusDriver * _bus
virtual bool start_measurements()
uint8_t _compass_instance