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_IIS2MDC.cpp
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
* https://www.st.com/resource/en/datasheet/iis2mdc.pdf
16
*
17
*/
18
#include "AP_Compass_config.h"
19
20
#if AP_COMPASS_IIS2MDC_ENABLED
21
22
#include "AP_Compass_IIS2MDC.h"
23
24
// IIS2MDC Registers
25
#define IIS2MDC_ADDR_CFG_REG_A 0x60
26
#define IIS2MDC_ADDR_CFG_REG_B 0x61
27
#define IIS2MDC_ADDR_CFG_REG_C 0x62
28
#define IIS2MDC_ADDR_STATUS_REG 0x67
29
#define IIS2MDC_ADDR_OUTX_L_REG 0x68
30
#define IIS2MDC_ADDR_WHO_AM_I 0x4F
31
32
// IIS2MDC Definitions
33
#define IIS2MDC_WHO_AM_I 0b01000000
34
#define IIS2MDC_STATUS_REG_READY 0b00001111
35
// CFG_REG_A
36
#define COMP_TEMP_EN (1 << 7)
37
#define MD_CONTINUOUS (0 << 0)
38
#define ODR_100 ((1 << 3) | (1 << 2))
39
// CFG_REG_B
40
#define OFF_CANC (1 << 1)
41
// CFG_REG_C
42
#define BDU (1 << 4)
43
44
extern const AP_HAL::HAL &hal;
45
46
AP_Compass_Backend *AP_Compass_IIS2MDC::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
47
bool force_external,
48
enum Rotation rotation)
49
{
50
if (!dev) {
51
return nullptr;
52
}
53
54
AP_Compass_IIS2MDC *sensor = NEW_NOTHROW AP_Compass_IIS2MDC(std::move(dev),force_external,rotation);
55
56
if (!sensor || !sensor->init()) {
57
delete sensor;
58
return nullptr;
59
}
60
61
return sensor;
62
}
63
64
AP_Compass_IIS2MDC::AP_Compass_IIS2MDC(AP_HAL::OwnPtr<AP_HAL::Device> dev,
65
bool force_external,
66
enum Rotation rotation)
67
: _dev(std::move(dev))
68
, _rotation(rotation)
69
, _force_external(force_external)
70
{
71
}
72
73
bool AP_Compass_IIS2MDC::init()
74
{
75
WITH_SEMAPHORE(_dev->get_semaphore());
76
77
_dev->set_retries(10);
78
79
if (!check_whoami()) {
80
return false;
81
}
82
83
if (!_dev->write_register(IIS2MDC_ADDR_CFG_REG_A, MD_CONTINUOUS | ODR_100 | COMP_TEMP_EN)) {
84
return false;
85
}
86
87
if (!_dev->write_register(IIS2MDC_ADDR_CFG_REG_B, OFF_CANC)) {
88
return false;
89
}
90
91
if (!_dev->write_register(IIS2MDC_ADDR_CFG_REG_C, BDU)) {
92
return false;
93
}
94
95
// lower retries for run
96
_dev->set_retries(3);
97
98
// register compass instance
99
_dev->set_device_type(DEVTYPE_IIS2MDC);
100
101
if (!register_compass(_dev->get_bus_id(), _instance)) {
102
return false;
103
}
104
105
set_dev_id(_instance, _dev->get_bus_id());
106
107
set_rotation(_instance, _rotation);
108
109
if (_force_external) {
110
set_external(_instance, true);
111
}
112
113
// Enable 100HZ
114
_dev->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_IIS2MDC::timer, void));
115
116
return true;
117
}
118
119
bool AP_Compass_IIS2MDC::check_whoami()
120
{
121
uint8_t whoami = 0;
122
if (!_dev->read_registers(IIS2MDC_ADDR_WHO_AM_I, &whoami, 1)){
123
return false;
124
}
125
126
return whoami == IIS2MDC_WHO_AM_I;
127
}
128
129
void AP_Compass_IIS2MDC::timer()
130
{
131
struct PACKED {
132
uint8_t xout0;
133
uint8_t xout1;
134
uint8_t yout0;
135
uint8_t yout1;
136
uint8_t zout0;
137
uint8_t zout1;
138
uint8_t tout0;
139
uint8_t tout1;
140
} buffer;
141
142
const float range_scale = 100.f / 65.535f; // +/- 50,000 milligauss, 16bit
143
144
uint8_t status = 0;
145
if (!_dev->read_registers(IIS2MDC_ADDR_STATUS_REG, &status, 1)) {
146
return;
147
}
148
149
if (!(status & IIS2MDC_STATUS_REG_READY)) {
150
return;
151
}
152
153
if (!_dev->read_registers(IIS2MDC_ADDR_OUTX_L_REG, (uint8_t *) &buffer, sizeof(buffer))) {
154
return;
155
}
156
157
const int16_t x = ((buffer.xout1 << 8) | buffer.xout0);
158
const int16_t y = ((buffer.yout1 << 8) | buffer.yout0);
159
const int16_t z = -1 * ((buffer.zout1 << 8) | buffer.zout0);
160
161
Vector3f field{ x * range_scale, y * range_scale, z * range_scale };
162
163
accumulate_sample(field, _instance);
164
}
165
166
void AP_Compass_IIS2MDC::read()
167
{
168
drain_accumulated_samples(_instance);
169
}
170
171
#endif //AP_COMPASS_IIS2MDC_ENABLED
172
173