Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/AP_Compass_AK8963.h
9692 views
1
#pragma once
2
3
#include "AP_Compass_config.h"
4
5
#if AP_COMPASS_AK8963_ENABLED
6
7
#include <AP_Common/AP_Common.h>
8
#include <AP_HAL/AP_HAL.h>
9
#include <AP_HAL/Device.h>
10
#include <AP_Math/AP_Math.h>
11
12
#include "AP_Compass.h"
13
#include "AP_Compass_Backend.h"
14
15
class AuxiliaryBus;
16
class AuxiliaryBusSlave;
17
class AP_InertialSensor;
18
class AP_AK8963_BusDriver;
19
20
class AP_Compass_AK8963 : public AP_Compass_Backend
21
{
22
public:
23
/* Probe for AK8963 standalone on I2C bus */
24
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
25
enum Rotation rotation);
26
27
/* Probe for AK8963 on auxiliary bus of MPU9250, connected through I2C */
28
static AP_Compass_Backend *probe_mpu9250(AP_HAL::OwnPtr<AP_HAL::Device> dev,
29
enum Rotation rotation);
30
31
/* Probe for AK8963 on auxiliary bus of MPU9250, connected through SPI */
32
static AP_Compass_Backend *probe_mpu9250(uint8_t mpu9250_instance,
33
enum Rotation rotation);
34
35
static constexpr const char *name = "AK8963";
36
37
virtual ~AP_Compass_AK8963();
38
39
void read() override;
40
41
/* Must be public so the BusDriver can access its definition */
42
struct PACKED sample_regs {
43
int16_t val[3];
44
uint8_t st2;
45
};
46
47
private:
48
AP_Compass_AK8963(AP_AK8963_BusDriver *bus,
49
enum Rotation rotation);
50
51
bool init();
52
void _make_factory_sensitivity_adjustment(Vector3f &field) const;
53
void _make_adc_sensitivity_adjustment(Vector3f &field) const;
54
55
bool _reset();
56
bool _setup_mode();
57
bool _check_id();
58
bool _calibrate();
59
60
void _update();
61
62
AP_AK8963_BusDriver *_bus;
63
64
float _magnetometer_ASA[3] {0, 0, 0};
65
66
bool _initialized;
67
enum Rotation _rotation;
68
};
69
70
class AP_AK8963_BusDriver
71
{
72
public:
73
virtual ~AP_AK8963_BusDriver() { }
74
75
virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;
76
virtual bool register_read(uint8_t reg, uint8_t *val) = 0;
77
virtual bool register_write(uint8_t reg, uint8_t val) = 0;
78
79
virtual AP_HAL::Semaphore *get_semaphore() = 0;
80
81
virtual bool configure() { return true; }
82
virtual bool start_measurements() { return true; }
83
virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;
84
85
// set device type within a device class
86
virtual void set_device_type(uint8_t devtype) = 0;
87
88
// return 24 bit bus identifier
89
virtual uint32_t get_bus_id(void) const = 0;
90
};
91
92
class AP_AK8963_BusDriver_HALDevice: public AP_AK8963_BusDriver
93
{
94
public:
95
AP_AK8963_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev);
96
97
virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
98
virtual bool register_read(uint8_t reg, uint8_t *val) override;
99
virtual bool register_write(uint8_t reg, uint8_t val) override;
100
101
virtual AP_HAL::Semaphore *get_semaphore() override;
102
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
103
104
// set device type within a device class
105
void set_device_type(uint8_t devtype) override {
106
_dev->set_device_type(devtype);
107
}
108
109
// return 24 bit bus identifier
110
uint32_t get_bus_id(void) const override {
111
return _dev->get_bus_id();
112
}
113
114
private:
115
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
116
};
117
118
class AP_AK8963_BusDriver_Auxiliary : public AP_AK8963_BusDriver
119
{
120
public:
121
AP_AK8963_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
122
uint8_t backend_instance, uint8_t addr);
123
~AP_AK8963_BusDriver_Auxiliary();
124
125
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
126
bool register_read(uint8_t reg, uint8_t *val) override;
127
bool register_write(uint8_t reg, uint8_t val) override;
128
129
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
130
131
AP_HAL::Semaphore *get_semaphore() override;
132
133
bool configure() override;
134
bool start_measurements() override;
135
136
// set device type within a device class
137
void set_device_type(uint8_t devtype) override;
138
139
// return 24 bit bus identifier
140
uint32_t get_bus_id(void) const override;
141
142
private:
143
AuxiliaryBus *_bus;
144
AuxiliaryBusSlave *_slave;
145
bool _started;
146
};
147
148
#endif // AP_COMPASS_AK8963_ENABLED
149
150