24 #define AK8963_I2C_ADDR 0x0c 26 #define AK8963_WIA 0x00 27 # define AK8963_Device_ID 0x48 29 #define AK8963_HXL 0x03 32 #define AK8963_CNTL1 0x0A 33 # define AK8963_CONTINUOUS_MODE1 0x02 34 # define AK8963_CONTINUOUS_MODE2 0x06 35 # define AK8963_SELFTEST_MODE 0x08 36 # define AK8963_POWERDOWN_MODE 0x00 37 # define AK8963_FUSE_MODE 0x0f 38 # define AK8963_16BIT_ADC 0x10 39 # define AK8963_14BIT_ADC 0x00 41 #define AK8963_CNTL2 0x0B 42 # define AK8963_RESET 0x01 44 #define AK8963_ASAX 0x10 46 #define AK8963_MILLIGAUSS_SCALE 10.0f 81 if (!sensor || !sensor->
init()) {
101 return probe(compass, std::move(dev), rotation);
116 if (!sensor || !sensor->
init()) {
129 hal.
console->
printf(
"AK8963: Unable to get bus semaphore\n");
134 hal.
console->
printf(
"AK8963: Could not configure the bus\n");
144 hal.
console->
printf(
"AK8963: Could not read calibration data\n");
154 hal.
console->
printf(
"AK8963: Could not start measurements\n");
202 static const float ADC_16BIT_RESOLUTION = 0.15f;
204 field *= ADC_16BIT_RESOLUTION;
225 if ((regs.st2 & 0x08)) {
229 raw_field =
Vector3f(regs.val[0], regs.val[1], regs.val[2]);
265 for (
int i = 0; i < 5; i++) {
266 uint8_t deviceid = 0;
297 for (
int i = 0; i < 3; i++) {
298 float data = response[i];
307 : _dev(
std::move(dev))
338 uint8_t backend_instance, uint8_t addr)
369 int n = _slave->read(buf);
370 return n ==
static_cast<int>(size);
373 int r = _slave->passthrough_read(reg, buf, size);
375 return r > 0 &&
static_cast<uint32_t
>(r) == size;
380 return _slave->passthrough_read(reg, val, 1) == 1;
385 return _slave->passthrough_write(reg, val) == 1;
390 return _bus ? _bus->get_semaphore() :
nullptr;
395 if (!_bus || !_slave) {
414 return _bus->register_periodic_callback(period_usec, cb);
420 _bus->set_device_type(devtype);
426 return _bus->get_bus_id();
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
bool start_measurements()
Vector3< float > Vector3f
#define HAL_INS_MPU9250_SPI
virtual bool register_read(uint8_t reg, uint8_t *val)=0
float _magnetometer_ASA[3]
virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size)=0
AP_HAL::UARTDriver * console
void rotate_field(Vector3f &mag, uint8_t instance)
virtual Semaphore * get_semaphore() override=0
void set_device_type(uint8_t devtype) override
virtual void set_device_type(uint8_t devtype)=0
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
virtual AP_HAL::Semaphore * get_semaphore() override
void correct_field(Vector3f &mag, uint8_t i)
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override
virtual bool register_read(uint8_t reg, uint8_t *val) override
bool register_write(uint8_t reg, uint8_t val) override
void set_dev_id(uint8_t instance, uint32_t dev_id)
#define AK8963_MILLIGAUSS_SCALE
virtual bool register_write(uint8_t reg, uint8_t val)=0
void fail(const char *why)
static AP_InertialSensor ins
~AP_AK8963_BusDriver_Auxiliary()
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
virtual void printf(const char *,...) FMT_PRINTF(2
virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb)=0
virtual bool take_nonblocking() WARN_IF_UNUSED=0
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
uint8_t register_compass(void) const
bool is_zero(const T fVal1)
void _make_factory_sensitivity_adjustment(Vector3f &field) const
AuxiliaryBusSlave * request_next_slave(uint8_t addr)
#define AK8963_CONTINUOUS_MODE2
AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
AP_HAL::Semaphore * get_semaphore() override
static AP_Compass_Backend * probe_mpu9250(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
bool register_read(uint8_t reg, uint8_t *val) override
AP_Compass_AK8963(Compass &compass, AP_AK8963_BusDriver *bus, enum Rotation rotation=ROTATION_NONE)
void detect_backends(void)
void _make_adc_sensitivity_adjustment(Vector3f &field) const
AP_AK8963_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id, uint8_t backend_instance, uint8_t addr)
virtual ~AP_Compass_AK8963()
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override
void set_rotation(uint8_t instance, enum Rotation rotation)
AuxiliaryBus * get_auxiliary_bus(int16_t backend_id)
uint32_t get_bus_id(void) const override
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
virtual AP_HAL::Semaphore * get_semaphore()=0
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
AP_AK8963_BusDriver * _bus
void publish_raw_field(const Vector3f &mag, uint8_t instance)
virtual bool start_measurements()
virtual bool register_write(uint8_t reg, uint8_t val) override
static AP_InertialSensor * get_instance()
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
virtual uint32_t get_bus_id(void) const =0
uint8_t _compass_instance