2016-11-24 03:46:47 -04:00
|
|
|
/*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
|
2023-02-19 21:05:04 -04:00
|
|
|
#include "AP_Compass_config.h"
|
|
|
|
|
|
|
|
#if AP_COMPASS_AK09916_ENABLED
|
|
|
|
|
2016-11-24 03:46:47 -04:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_HAL/I2CDevice.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
|
|
|
|
#include "AP_Compass.h"
|
|
|
|
#include "AP_Compass_Backend.h"
|
|
|
|
|
|
|
|
#ifndef HAL_COMPASS_AK09916_I2C_ADDR
|
|
|
|
# define HAL_COMPASS_AK09916_I2C_ADDR 0x0C
|
|
|
|
#endif
|
|
|
|
|
2019-03-05 08:22:03 -04:00
|
|
|
|
|
|
|
#ifndef HAL_COMPASS_ICM20948_I2C_ADDR
|
|
|
|
# define HAL_COMPASS_ICM20948_I2C_ADDR 0x69
|
|
|
|
#endif
|
|
|
|
|
2021-04-12 01:08:53 -03:00
|
|
|
#ifndef HAL_COMPASS_ICM20948_I2C_ADDR2
|
|
|
|
# define HAL_COMPASS_ICM20948_I2C_ADDR2 0x68
|
|
|
|
#endif
|
|
|
|
|
2019-02-15 08:03:04 -04:00
|
|
|
class AuxiliaryBus;
|
|
|
|
class AuxiliaryBusSlave;
|
|
|
|
class AP_InertialSensor;
|
|
|
|
class AP_AK09916_BusDriver;
|
2017-05-24 05:45:19 -03:00
|
|
|
|
2016-11-24 03:46:47 -04:00
|
|
|
class AP_Compass_AK09916 : public AP_Compass_Backend
|
|
|
|
{
|
|
|
|
public:
|
2019-02-15 08:03:04 -04:00
|
|
|
/* Probe for AK09916 standalone on I2C bus */
|
2018-08-06 19:21:27 -03:00
|
|
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
2019-02-15 08:03:04 -04:00
|
|
|
bool force_external,
|
2019-09-01 19:17:05 -03:00
|
|
|
enum Rotation rotation);
|
2016-11-24 03:46:47 -04:00
|
|
|
|
2023-02-19 21:05:07 -04:00
|
|
|
#if AP_COMPASS_ICM20948_ENABLED
|
2019-02-15 08:03:04 -04:00
|
|
|
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through I2C */
|
2018-08-06 19:21:27 -03:00
|
|
|
static AP_Compass_Backend *probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
2019-03-05 08:22:03 -04:00
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,
|
2019-02-15 08:03:04 -04:00
|
|
|
bool force_external,
|
2019-09-01 19:17:05 -03:00
|
|
|
enum Rotation rotation);
|
2019-02-15 08:03:04 -04:00
|
|
|
|
2021-10-27 05:06:32 -03:00
|
|
|
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through SPI by default */
|
|
|
|
static AP_Compass_Backend *probe_ICM20948(uint8_t mpu9250_instance, enum Rotation rotation);
|
|
|
|
static AP_Compass_Backend *probe_ICM20948_SPI(uint8_t mpu9250_instance,
|
|
|
|
enum Rotation rotation);
|
|
|
|
|
|
|
|
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through I2C */
|
|
|
|
static AP_Compass_Backend *probe_ICM20948_I2C(uint8_t mpu9250_instance,
|
2019-09-01 19:17:05 -03:00
|
|
|
enum Rotation rotation);
|
2023-02-19 21:05:07 -04:00
|
|
|
#endif
|
2016-11-24 03:46:47 -04:00
|
|
|
|
|
|
|
static constexpr const char *name = "AK09916";
|
|
|
|
|
2019-02-15 08:03:04 -04:00
|
|
|
virtual ~AP_Compass_AK09916();
|
|
|
|
|
|
|
|
void read() override;
|
|
|
|
|
2023-10-28 14:58:32 -03:00
|
|
|
/* Must be public so the BusDriver can access its definition */
|
|
|
|
struct PACKED sample_regs {
|
|
|
|
uint8_t st1;
|
|
|
|
int16_t val[3];
|
|
|
|
uint8_t tmps;
|
|
|
|
uint8_t st2;
|
|
|
|
};
|
|
|
|
|
2016-11-24 03:46:47 -04:00
|
|
|
private:
|
2019-02-15 08:03:04 -04:00
|
|
|
AP_Compass_AK09916(AP_AK09916_BusDriver *bus, bool force_external,
|
2019-09-01 19:17:05 -03:00
|
|
|
enum Rotation rotation);
|
2019-02-15 08:03:04 -04:00
|
|
|
|
|
|
|
bool init();
|
|
|
|
void _make_factory_sensitivity_adjustment(Vector3f &field) const;
|
|
|
|
void _make_adc_sensitivity_adjustment(Vector3f &field) const;
|
|
|
|
|
|
|
|
bool _reset();
|
|
|
|
bool _setup_mode();
|
|
|
|
bool _check_id();
|
|
|
|
bool _calibrate();
|
|
|
|
|
|
|
|
void _update();
|
|
|
|
|
|
|
|
AP_AK09916_BusDriver *_bus;
|
|
|
|
|
|
|
|
bool _force_external;
|
|
|
|
uint8_t _compass_instance;
|
|
|
|
bool _initialized;
|
|
|
|
enum Rotation _rotation;
|
2021-10-05 17:12:27 -03:00
|
|
|
enum AP_Compass_Backend::DevTypes _devtype;
|
2023-07-07 02:03:49 -03:00
|
|
|
uint8_t no_data;
|
2019-02-15 08:03:04 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
class AP_AK09916_BusDriver
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
virtual ~AP_AK09916_BusDriver() { }
|
|
|
|
|
|
|
|
virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;
|
|
|
|
virtual bool register_read(uint8_t reg, uint8_t *val) = 0;
|
2021-12-18 21:30:57 -04:00
|
|
|
virtual bool register_write(uint8_t reg, uint8_t val, bool checked=false) = 0;
|
2019-02-15 08:03:04 -04:00
|
|
|
|
|
|
|
virtual AP_HAL::Semaphore *get_semaphore() = 0;
|
|
|
|
|
|
|
|
virtual bool configure() { return true; }
|
|
|
|
virtual bool start_measurements() { return true; }
|
|
|
|
virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;
|
|
|
|
|
|
|
|
// set device type within a device class
|
|
|
|
virtual void set_device_type(uint8_t devtype) = 0;
|
|
|
|
|
|
|
|
// return 24 bit bus identifier
|
|
|
|
virtual uint32_t get_bus_id(void) const = 0;
|
2021-12-18 21:30:57 -04:00
|
|
|
|
|
|
|
/**
|
|
|
|
setup for register value checking. Frequency is how often to
|
|
|
|
check registers. If set to 10 then every 10th call to
|
|
|
|
check_next_register will check a register
|
|
|
|
*/
|
|
|
|
virtual void setup_checked_registers(uint8_t num_regs) {}
|
|
|
|
virtual void check_next_register(void) {}
|
2019-02-15 08:03:04 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
class AP_AK09916_BusDriver_HALDevice: public AP_AK09916_BusDriver
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
AP_AK09916_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
|
|
|
|
|
|
|
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;
|
2021-12-18 21:30:57 -04:00
|
|
|
virtual bool register_write(uint8_t reg, uint8_t val, bool checked) override;
|
2019-02-15 08:03:04 -04:00
|
|
|
|
|
|
|
virtual AP_HAL::Semaphore *get_semaphore() override;
|
|
|
|
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
|
|
|
|
|
|
|
|
// set device type within a device class
|
|
|
|
void set_device_type(uint8_t devtype) override {
|
|
|
|
_dev->set_device_type(devtype);
|
|
|
|
}
|
|
|
|
|
|
|
|
// return 24 bit bus identifier
|
|
|
|
uint32_t get_bus_id(void) const override {
|
|
|
|
return _dev->get_bus_id();
|
|
|
|
}
|
2021-12-18 21:30:57 -04:00
|
|
|
|
|
|
|
/**
|
|
|
|
setup for register value checking. Frequency is how often to
|
|
|
|
check registers. If set to 10 then every 10th call to
|
|
|
|
check_next_register will check a register
|
|
|
|
*/
|
|
|
|
void setup_checked_registers(uint8_t num_regs) override {
|
|
|
|
_dev->setup_checked_registers(num_regs);
|
|
|
|
}
|
|
|
|
void check_next_register(void) override {
|
|
|
|
_dev->check_next_register();
|
|
|
|
}
|
2017-05-24 05:45:19 -03:00
|
|
|
|
2019-02-15 08:03:04 -04:00
|
|
|
private:
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
|
|
|
|
};
|
|
|
|
|
|
|
|
class AP_AK09916_BusDriver_Auxiliary : public AP_AK09916_BusDriver
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
AP_AK09916_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
|
|
|
|
uint8_t backend_instance, uint8_t addr);
|
|
|
|
~AP_AK09916_BusDriver_Auxiliary();
|
|
|
|
|
|
|
|
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
|
|
|
|
bool register_read(uint8_t reg, uint8_t *val) override;
|
2021-12-18 21:30:57 -04:00
|
|
|
bool register_write(uint8_t reg, uint8_t val, bool checked) override;
|
2019-02-15 08:03:04 -04:00
|
|
|
|
|
|
|
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
|
2016-11-24 03:46:47 -04:00
|
|
|
|
2019-02-15 08:03:04 -04:00
|
|
|
AP_HAL::Semaphore *get_semaphore() override;
|
|
|
|
|
|
|
|
bool configure() override;
|
|
|
|
bool start_measurements() override;
|
|
|
|
|
|
|
|
// set device type within a device class
|
|
|
|
void set_device_type(uint8_t devtype) override;
|
2016-11-24 03:46:47 -04:00
|
|
|
|
2019-02-15 08:03:04 -04:00
|
|
|
// return 24 bit bus identifier
|
|
|
|
uint32_t get_bus_id(void) const override;
|
|
|
|
|
|
|
|
private:
|
|
|
|
AuxiliaryBus *_bus;
|
|
|
|
AuxiliaryBusSlave *_slave;
|
|
|
|
bool _started;
|
2016-11-24 03:46:47 -04:00
|
|
|
};
|
2023-02-19 21:05:04 -04:00
|
|
|
|
|
|
|
#endif // AP_COMPASS_AK09916_ENABLED
|