CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/AP_Compass_AK09916.h
Views: 1798
1
/*
2
* This file is free software: you can redistribute it and/or modify it
3
* under the terms of the GNU General Public License as published by the
4
* Free Software Foundation, either version 3 of the License, or
5
* (at your option) any later version.
6
*
7
* This file is distributed in the hope that it will be useful, but
8
* WITHOUT ANY WARRANTY; without even the implied warranty of
9
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10
* See the GNU General Public License for more details.
11
*
12
* You should have received a copy of the GNU General Public License along
13
* with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
#pragma once
16
17
#include "AP_Compass_config.h"
18
19
#if AP_COMPASS_AK09916_ENABLED
20
21
#include <AP_Common/AP_Common.h>
22
#include <AP_HAL/AP_HAL.h>
23
#include <AP_HAL/I2CDevice.h>
24
#include <AP_Math/AP_Math.h>
25
26
#include "AP_Compass.h"
27
#include "AP_Compass_Backend.h"
28
29
#ifndef HAL_COMPASS_AK09916_I2C_ADDR
30
# define HAL_COMPASS_AK09916_I2C_ADDR 0x0C
31
#endif
32
33
34
#ifndef HAL_COMPASS_ICM20948_I2C_ADDR
35
# define HAL_COMPASS_ICM20948_I2C_ADDR 0x69
36
#endif
37
38
#ifndef HAL_COMPASS_ICM20948_I2C_ADDR2
39
# define HAL_COMPASS_ICM20948_I2C_ADDR2 0x68
40
#endif
41
42
class AuxiliaryBus;
43
class AuxiliaryBusSlave;
44
class AP_InertialSensor;
45
class AP_AK09916_BusDriver;
46
47
class AP_Compass_AK09916 : public AP_Compass_Backend
48
{
49
public:
50
/* Probe for AK09916 standalone on I2C bus */
51
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
52
bool force_external,
53
enum Rotation rotation);
54
55
#if AP_COMPASS_ICM20948_ENABLED
56
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through I2C */
57
static AP_Compass_Backend *probe_ICM20948(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
58
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_icm,
59
bool force_external,
60
enum Rotation rotation);
61
62
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through SPI by default */
63
static AP_Compass_Backend *probe_ICM20948(uint8_t mpu9250_instance, enum Rotation rotation);
64
static AP_Compass_Backend *probe_ICM20948_SPI(uint8_t mpu9250_instance,
65
enum Rotation rotation);
66
67
/* Probe for AK09916 on auxiliary bus of ICM20948, connected through I2C */
68
static AP_Compass_Backend *probe_ICM20948_I2C(uint8_t mpu9250_instance,
69
enum Rotation rotation);
70
#endif
71
72
static constexpr const char *name = "AK09916";
73
74
virtual ~AP_Compass_AK09916();
75
76
void read() override;
77
78
/* Must be public so the BusDriver can access its definition */
79
struct PACKED sample_regs {
80
uint8_t st1;
81
int16_t val[3];
82
uint8_t tmps;
83
uint8_t st2;
84
};
85
86
private:
87
AP_Compass_AK09916(AP_AK09916_BusDriver *bus, bool force_external,
88
enum Rotation rotation);
89
90
bool init();
91
void _make_factory_sensitivity_adjustment(Vector3f &field) const;
92
void _make_adc_sensitivity_adjustment(Vector3f &field) const;
93
94
bool _reset();
95
bool _setup_mode();
96
bool _check_id();
97
bool _calibrate();
98
99
void _update();
100
101
AP_AK09916_BusDriver *_bus;
102
103
bool _force_external;
104
uint8_t _compass_instance;
105
bool _initialized;
106
enum Rotation _rotation;
107
enum AP_Compass_Backend::DevTypes _devtype;
108
uint8_t no_data;
109
};
110
111
112
class AP_AK09916_BusDriver
113
{
114
public:
115
virtual ~AP_AK09916_BusDriver() { }
116
117
virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;
118
virtual bool register_read(uint8_t reg, uint8_t *val) = 0;
119
virtual bool register_write(uint8_t reg, uint8_t val, bool checked=false) = 0;
120
121
virtual AP_HAL::Semaphore *get_semaphore() = 0;
122
123
virtual bool configure() { return true; }
124
virtual bool start_measurements() { return true; }
125
virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;
126
127
// set device type within a device class
128
virtual void set_device_type(uint8_t devtype) = 0;
129
130
// return 24 bit bus identifier
131
virtual uint32_t get_bus_id(void) const = 0;
132
133
/**
134
setup for register value checking. Frequency is how often to
135
check registers. If set to 10 then every 10th call to
136
check_next_register will check a register
137
*/
138
virtual void setup_checked_registers(uint8_t num_regs) {}
139
virtual void check_next_register(void) {}
140
};
141
142
class AP_AK09916_BusDriver_HALDevice: public AP_AK09916_BusDriver
143
{
144
public:
145
AP_AK09916_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
146
147
virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
148
virtual bool register_read(uint8_t reg, uint8_t *val) override;
149
virtual bool register_write(uint8_t reg, uint8_t val, bool checked) override;
150
151
virtual AP_HAL::Semaphore *get_semaphore() override;
152
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
153
154
// set device type within a device class
155
void set_device_type(uint8_t devtype) override {
156
_dev->set_device_type(devtype);
157
}
158
159
// return 24 bit bus identifier
160
uint32_t get_bus_id(void) const override {
161
return _dev->get_bus_id();
162
}
163
164
/**
165
setup for register value checking. Frequency is how often to
166
check registers. If set to 10 then every 10th call to
167
check_next_register will check a register
168
*/
169
void setup_checked_registers(uint8_t num_regs) override {
170
_dev->setup_checked_registers(num_regs);
171
}
172
void check_next_register(void) override {
173
_dev->check_next_register();
174
}
175
176
private:
177
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
178
};
179
180
class AP_AK09916_BusDriver_Auxiliary : public AP_AK09916_BusDriver
181
{
182
public:
183
AP_AK09916_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
184
uint8_t backend_instance, uint8_t addr);
185
~AP_AK09916_BusDriver_Auxiliary();
186
187
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
188
bool register_read(uint8_t reg, uint8_t *val) override;
189
bool register_write(uint8_t reg, uint8_t val, bool checked) override;
190
191
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
192
193
AP_HAL::Semaphore *get_semaphore() override;
194
195
bool configure() override;
196
bool start_measurements() override;
197
198
// set device type within a device class
199
void set_device_type(uint8_t devtype) override;
200
201
// return 24 bit bus identifier
202
uint32_t get_bus_id(void) const override;
203
204
private:
205
AuxiliaryBus *_bus;
206
AuxiliaryBusSlave *_slave;
207
bool _started;
208
};
209
210
#endif // AP_COMPASS_AK09916_ENABLED
211
212