APM:Libraries
AP_Compass_AK8963.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_HAL/AP_HAL.h>
5 #include <AP_HAL/I2CDevice.h>
6 #include <AP_HAL/SPIDevice.h>
7 #include <AP_Math/AP_Math.h>
8 
9 #include "AP_Compass.h"
10 #include "AP_Compass_Backend.h"
11 
12 class AuxiliaryBus;
13 class AuxiliaryBusSlave;
14 class AP_InertialSensor;
16 
18 {
19 public:
20  /* Probe for AK8963 standalone on I2C bus */
23  enum Rotation rotation = ROTATION_NONE);
24 
25  /* Probe for AK8963 on auxiliary bus of MPU9250, connected through I2C */
26  static AP_Compass_Backend *probe_mpu9250(Compass &compass,
28  enum Rotation rotation = ROTATION_NONE);
29 
30  /* Probe for AK8963 on auxiliary bus of MPU9250, connected through SPI */
31  static AP_Compass_Backend *probe_mpu9250(Compass &compass, uint8_t mpu9250_instance,
32  enum Rotation rotation = ROTATION_NONE);
33 
34  static constexpr const char *name = "AK8963";
35 
36  virtual ~AP_Compass_AK8963();
37 
38  void read() override;
39 
40 private:
42  enum Rotation rotation = ROTATION_NONE);
43 
44  bool init();
46  void _make_adc_sensitivity_adjustment(Vector3f &field) const;
47 
48  bool _reset();
49  bool _setup_mode();
50  bool _check_id();
51  bool _calibrate();
52 
53  void _update();
54 
56 
57  float _magnetometer_ASA[3] {0, 0, 0};
58  float _mag_x_accum;
59  float _mag_y_accum;
60  float _mag_z_accum;
61  uint32_t _accum_count;
62 
66 };
67 
69 {
70 public:
71  virtual ~AP_AK8963_BusDriver() { }
72 
73  virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;
74  virtual bool register_read(uint8_t reg, uint8_t *val) = 0;
75  virtual bool register_write(uint8_t reg, uint8_t val) = 0;
76 
77  virtual AP_HAL::Semaphore *get_semaphore() = 0;
78 
79  virtual bool configure() { return true; }
80  virtual bool start_measurements() { return true; }
81  virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;
82 
83  // set device type within a device class
84  virtual void set_device_type(uint8_t devtype) = 0;
85 
86  // return 24 bit bus identifier
87  virtual uint32_t get_bus_id(void) const = 0;
88 };
89 
91 {
92 public:
94 
95  virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
96  virtual bool register_read(uint8_t reg, uint8_t *val) override;
97  virtual bool register_write(uint8_t reg, uint8_t val) override;
98 
99  virtual AP_HAL::Semaphore *get_semaphore() override;
100  AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
101 
102  // set device type within a device class
103  void set_device_type(uint8_t devtype) override {
104  _dev->set_device_type(devtype);
105  }
106 
107  // return 24 bit bus identifier
108  uint32_t get_bus_id(void) const override {
109  return _dev->get_bus_id();
110  }
111 
112 private:
114 };
115 
117 {
118 public:
120  uint8_t backend_instance, uint8_t addr);
122 
123  bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
124  bool register_read(uint8_t reg, uint8_t *val) override;
125  bool register_write(uint8_t reg, uint8_t val) override;
126 
127  AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
128 
129  AP_HAL::Semaphore *get_semaphore() override;
130 
131  bool configure();
132  bool start_measurements();
133 
134  // set device type within a device class
135  void set_device_type(uint8_t devtype) override;
136 
137  // return 24 bit bus identifier
138  uint32_t get_bus_id(void) const override;
139 
140 private:
143  bool _started;
144 };
static constexpr const char * name
Rotation
Definition: rotations.h:27
virtual bool configure()
static AP_InertialSensor ins
Definition: AHRS_Test.cpp:18
virtual ~AP_AK8963_BusDriver()
#define constexpr
Definition: AP_HAL_Macros.h:16
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
Definition: ICM20789.cpp:16
void _make_factory_sensitivity_adjustment(Vector3f &field) const
void set_device_type(uint8_t devtype) override
void * PeriodicHandle
Definition: Device.h:42
void read() override
static AP_Compass_Backend * probe_mpu9250(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
static Compass compass
Definition: AHRS_Test.cpp:20
AP_Compass_AK8963(Compass &compass, AP_AK8963_BusDriver *bus, enum Rotation rotation=ROTATION_NONE)
Common definitions and utility routines for the ArduPilot libraries.
void _make_adc_sensitivity_adjustment(Vector3f &field) const
uint32_t get_bus_id(void) const override
enum Rotation _rotation
AP_AK8963_BusDriver * _bus
virtual bool start_measurements()