Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Compass/AP_Compass_AK09916.h
Views: 1798
/*1* This file is free software: you can redistribute it and/or modify it2* under the terms of the GNU General Public License as published by the3* Free Software Foundation, either version 3 of the License, or4* (at your option) any later version.5*6* This file is distributed in the hope that it will be useful, but7* WITHOUT ANY WARRANTY; without even the implied warranty of8* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.9* See the GNU General Public License for more details.10*11* You should have received a copy of the GNU General Public License along12* with this program. If not, see <http://www.gnu.org/licenses/>.13*/14#pragma once1516#include "AP_Compass_config.h"1718#if AP_COMPASS_AK09916_ENABLED1920#include <AP_Common/AP_Common.h>21#include <AP_HAL/AP_HAL.h>22#include <AP_HAL/I2CDevice.h>23#include <AP_Math/AP_Math.h>2425#include "AP_Compass.h"26#include "AP_Compass_Backend.h"2728#ifndef HAL_COMPASS_AK09916_I2C_ADDR29# define HAL_COMPASS_AK09916_I2C_ADDR 0x0C30#endif313233#ifndef HAL_COMPASS_ICM20948_I2C_ADDR34# define HAL_COMPASS_ICM20948_I2C_ADDR 0x6935#endif3637#ifndef HAL_COMPASS_ICM20948_I2C_ADDR238# define HAL_COMPASS_ICM20948_I2C_ADDR2 0x6839#endif4041class AuxiliaryBus;42class AuxiliaryBusSlave;43class AP_InertialSensor;44class AP_AK09916_BusDriver;4546class AP_Compass_AK09916 : public AP_Compass_Backend47{48public:49/* Probe for AK09916 standalone on I2C bus */50static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,51bool force_external,52enum Rotation rotation);5354#if AP_COMPASS_ICM20948_ENABLED55/* Probe for AK09916 on auxiliary bus of ICM20948, connected through I2C */56static AP_Compass_Backend *probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,57AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,58bool force_external,59enum Rotation rotation);6061/* Probe for AK09916 on auxiliary bus of ICM20948, connected through SPI by default */62static AP_Compass_Backend *probe_ICM20948(uint8_t mpu9250_instance, enum Rotation rotation);63static AP_Compass_Backend *probe_ICM20948_SPI(uint8_t mpu9250_instance,64enum Rotation rotation);6566/* Probe for AK09916 on auxiliary bus of ICM20948, connected through I2C */67static AP_Compass_Backend *probe_ICM20948_I2C(uint8_t mpu9250_instance,68enum Rotation rotation);69#endif7071static constexpr const char *name = "AK09916";7273virtual ~AP_Compass_AK09916();7475void read() override;7677/* Must be public so the BusDriver can access its definition */78struct PACKED sample_regs {79uint8_t st1;80int16_t val[3];81uint8_t tmps;82uint8_t st2;83};8485private:86AP_Compass_AK09916(AP_AK09916_BusDriver *bus, bool force_external,87enum Rotation rotation);8889bool init();90void _make_factory_sensitivity_adjustment(Vector3f &field) const;91void _make_adc_sensitivity_adjustment(Vector3f &field) const;9293bool _reset();94bool _setup_mode();95bool _check_id();96bool _calibrate();9798void _update();99100AP_AK09916_BusDriver *_bus;101102bool _force_external;103uint8_t _compass_instance;104bool _initialized;105enum Rotation _rotation;106enum AP_Compass_Backend::DevTypes _devtype;107uint8_t no_data;108};109110111class AP_AK09916_BusDriver112{113public:114virtual ~AP_AK09916_BusDriver() { }115116virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;117virtual bool register_read(uint8_t reg, uint8_t *val) = 0;118virtual bool register_write(uint8_t reg, uint8_t val, bool checked=false) = 0;119120virtual AP_HAL::Semaphore *get_semaphore() = 0;121122virtual bool configure() { return true; }123virtual bool start_measurements() { return true; }124virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;125126// set device type within a device class127virtual void set_device_type(uint8_t devtype) = 0;128129// return 24 bit bus identifier130virtual uint32_t get_bus_id(void) const = 0;131132/**133setup for register value checking. Frequency is how often to134check registers. If set to 10 then every 10th call to135check_next_register will check a register136*/137virtual void setup_checked_registers(uint8_t num_regs) {}138virtual void check_next_register(void) {}139};140141class AP_AK09916_BusDriver_HALDevice: public AP_AK09916_BusDriver142{143public:144AP_AK09916_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);145146virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;147virtual bool register_read(uint8_t reg, uint8_t *val) override;148virtual bool register_write(uint8_t reg, uint8_t val, bool checked) override;149150virtual AP_HAL::Semaphore *get_semaphore() override;151AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;152153// set device type within a device class154void set_device_type(uint8_t devtype) override {155_dev->set_device_type(devtype);156}157158// return 24 bit bus identifier159uint32_t get_bus_id(void) const override {160return _dev->get_bus_id();161}162163/**164setup for register value checking. Frequency is how often to165check registers. If set to 10 then every 10th call to166check_next_register will check a register167*/168void setup_checked_registers(uint8_t num_regs) override {169_dev->setup_checked_registers(num_regs);170}171void check_next_register(void) override {172_dev->check_next_register();173}174175private:176AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;177};178179class AP_AK09916_BusDriver_Auxiliary : public AP_AK09916_BusDriver180{181public:182AP_AK09916_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,183uint8_t backend_instance, uint8_t addr);184~AP_AK09916_BusDriver_Auxiliary();185186bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;187bool register_read(uint8_t reg, uint8_t *val) override;188bool register_write(uint8_t reg, uint8_t val, bool checked) override;189190AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;191192AP_HAL::Semaphore *get_semaphore() override;193194bool configure() override;195bool start_measurements() override;196197// set device type within a device class198void set_device_type(uint8_t devtype) override;199200// return 24 bit bus identifier201uint32_t get_bus_id(void) const override;202203private:204AuxiliaryBus *_bus;205AuxiliaryBusSlave *_slave;206bool _started;207};208209#endif // AP_COMPASS_AK09916_ENABLED210211212