Path: blob/master/libraries/AP_Compass/AP_Compass_AK8963.h
9692 views
#pragma once12#include "AP_Compass_config.h"34#if AP_COMPASS_AK8963_ENABLED56#include <AP_Common/AP_Common.h>7#include <AP_HAL/AP_HAL.h>8#include <AP_HAL/Device.h>9#include <AP_Math/AP_Math.h>1011#include "AP_Compass.h"12#include "AP_Compass_Backend.h"1314class AuxiliaryBus;15class AuxiliaryBusSlave;16class AP_InertialSensor;17class AP_AK8963_BusDriver;1819class AP_Compass_AK8963 : public AP_Compass_Backend20{21public:22/* Probe for AK8963 standalone on I2C bus */23static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,24enum Rotation rotation);2526/* Probe for AK8963 on auxiliary bus of MPU9250, connected through I2C */27static AP_Compass_Backend *probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::Device> dev,28enum Rotation rotation);2930/* Probe for AK8963 on auxiliary bus of MPU9250, connected through SPI */31static AP_Compass_Backend *probe_mpu9250(uint8_t mpu9250_instance,32enum Rotation rotation);3334static constexpr const char *name = "AK8963";3536virtual ~AP_Compass_AK8963();3738void read() override;3940/* Must be public so the BusDriver can access its definition */41struct PACKED sample_regs {42int16_t val[3];43uint8_t st2;44};4546private:47AP_Compass_AK8963(AP_AK8963_BusDriver *bus,48enum Rotation rotation);4950bool init();51void _make_factory_sensitivity_adjustment(Vector3f &field) const;52void _make_adc_sensitivity_adjustment(Vector3f &field) const;5354bool _reset();55bool _setup_mode();56bool _check_id();57bool _calibrate();5859void _update();6061AP_AK8963_BusDriver *_bus;6263float _magnetometer_ASA[3] {0, 0, 0};6465bool _initialized;66enum Rotation _rotation;67};6869class AP_AK8963_BusDriver70{71public:72virtual ~AP_AK8963_BusDriver() { }7374virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;75virtual bool register_read(uint8_t reg, uint8_t *val) = 0;76virtual bool register_write(uint8_t reg, uint8_t val) = 0;7778virtual AP_HAL::Semaphore *get_semaphore() = 0;7980virtual bool configure() { return true; }81virtual bool start_measurements() { return true; }82virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;8384// set device type within a device class85virtual void set_device_type(uint8_t devtype) = 0;8687// return 24 bit bus identifier88virtual uint32_t get_bus_id(void) const = 0;89};9091class AP_AK8963_BusDriver_HALDevice: public AP_AK8963_BusDriver92{93public:94AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev);9596virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;97virtual bool register_read(uint8_t reg, uint8_t *val) override;98virtual bool register_write(uint8_t reg, uint8_t val) override;99100virtual AP_HAL::Semaphore *get_semaphore() override;101AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;102103// set device type within a device class104void set_device_type(uint8_t devtype) override {105_dev->set_device_type(devtype);106}107108// return 24 bit bus identifier109uint32_t get_bus_id(void) const override {110return _dev->get_bus_id();111}112113private:114AP_HAL::OwnPtr<AP_HAL::Device> _dev;115};116117class AP_AK8963_BusDriver_Auxiliary : public AP_AK8963_BusDriver118{119public:120AP_AK8963_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,121uint8_t backend_instance, uint8_t addr);122~AP_AK8963_BusDriver_Auxiliary();123124bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;125bool register_read(uint8_t reg, uint8_t *val) override;126bool register_write(uint8_t reg, uint8_t val) override;127128AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;129130AP_HAL::Semaphore *get_semaphore() override;131132bool configure() override;133bool start_measurements() override;134135// set device type within a device class136void set_device_type(uint8_t devtype) override;137138// return 24 bit bus identifier139uint32_t get_bus_id(void) const override;140141private:142AuxiliaryBus *_bus;143AuxiliaryBusSlave *_slave;144bool _started;145};146147#endif // AP_COMPASS_AK8963_ENABLED148149150