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