21 bool force_external =
false,
35 bool force_external,
enum Rotation rotation);
76 virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;
77 virtual bool register_read(uint8_t reg, uint8_t *val) = 0;
78 virtual bool register_write(uint8_t reg, uint8_t val) = 0;
88 virtual void set_device_type(uint8_t devtype) = 0;
91 virtual uint32_t get_bus_id(
void)
const = 0;
101 bool block_read(uint8_t reg, uint8_t *buf, uint32_t size)
override;
102 bool register_read(uint8_t reg, uint8_t *val)
override;
103 bool register_write(uint8_t reg, uint8_t val)
override;
111 _dev->set_device_type(devtype);
116 return _dev->get_bus_id();
120 return _dev->set_retries(retries);
134 bool block_read(uint8_t reg, uint8_t *buf, uint32_t size)
override;
135 bool register_read(uint8_t reg, uint8_t *val)
override;
136 bool register_write(uint8_t reg, uint8_t val)
override;
140 bool configure()
override;
141 bool start_measurements()
override;
146 void set_device_type(uint8_t devtype)
override;
149 uint32_t get_bus_id(
void)
const override;
AP_HMC5843_BusDriver * _bus
AP_Compass_HMC5843(Compass &compass, AP_HMC5843_BusDriver *bus, bool force_external, enum Rotation rotation)
static constexpr const char * name
AP_HAL::OwnPtr< AP_HAL::Device > _dev
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
AuxiliaryBusSlave * _slave
static AP_InertialSensor ins
static AP_HAL::OwnPtr< AP_HAL::Device > dev
virtual ~AP_HMC5843_BusDriver()
bool _setup_sampling_mode()
virtual ~AP_Compass_HMC5843()
Common definitions and utility routines for the ArduPilot libraries.
void set_device_type(uint8_t devtype) override
virtual void set_retries(uint8_t retries)
void set_retries(uint8_t retries) override
virtual bool start_measurements()
uint8_t _compass_instance
static AP_Compass_Backend * probe_mpu6000(Compass &compass, enum Rotation rotation=ROTATION_NONE)
uint32_t get_bus_id(void) const override