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_IST8310.cpp
Views: 1798
1
/*
2
* Copyright (C) 2016 Emlid Ltd. All rights reserved.
3
*
4
* This file is free software: you can redistribute it and/or modify it
5
* under the terms of the GNU General Public License as published by the
6
* Free Software Foundation, either version 3 of the License, or
7
* (at your option) any later version.
8
*
9
* This file is distributed in the hope that it will be useful, but
10
* WITHOUT ANY WARRANTY; without even the implied warranty of
11
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12
* See the GNU General Public License for more details.
13
*
14
* You should have received a copy of the GNU General Public License along
15
* with this program. If not, see <http://www.gnu.org/licenses/>.
16
*
17
* Driver by Georgii Staroselskii, Sep 2016
18
*/
19
#include "AP_Compass_IST8310.h"
20
21
#if AP_COMPASS_IST8310_ENABLED
22
23
#include <stdio.h>
24
#include <utility>
25
26
#include <AP_HAL/AP_HAL.h>
27
#include <AP_HAL/utility/sparse-endian.h>
28
#include <AP_Math/AP_Math.h>
29
#include <AP_BoardConfig/AP_BoardConfig.h>
30
31
#define WAI_REG 0x0
32
#define DEVICE_ID 0x10
33
34
#define OUTPUT_X_L_REG 0x3
35
#define OUTPUT_X_H_REG 0x4
36
#define OUTPUT_Y_L_REG 0x5
37
#define OUTPUT_Y_H_REG 0x6
38
#define OUTPUT_Z_L_REG 0x7
39
#define OUTPUT_Z_H_REG 0x8
40
41
#define CNTL1_REG 0xA
42
#define CNTL1_VAL_SINGLE_MEASUREMENT_MODE 0x1
43
44
#define CNTL2_REG 0xB
45
#define CNTL2_VAL_SRST 1
46
47
#define AVGCNTL_REG 0x41
48
#define AVGCNTL_VAL_XZ_0 (0)
49
#define AVGCNTL_VAL_XZ_2 (1)
50
#define AVGCNTL_VAL_XZ_4 (2)
51
#define AVGCNTL_VAL_XZ_8 (3)
52
#define AVGCNTL_VAL_XZ_16 (4)
53
#define AVGCNTL_VAL_Y_0 (0 << 3)
54
#define AVGCNTL_VAL_Y_2 (1 << 3)
55
#define AVGCNTL_VAL_Y_4 (2 << 3)
56
#define AVGCNTL_VAL_Y_8 (3 << 3)
57
#define AVGCNTL_VAL_Y_16 (4 << 3)
58
59
#define PDCNTL_REG 0x42
60
#define PDCNTL_VAL_PULSE_DURATION_NORMAL 0xC0
61
62
#define SAMPLING_PERIOD_USEC (10 * AP_USEC_PER_MSEC)
63
64
/*
65
* FSR:
66
* x, y: +- 1600 µT
67
* z: +- 2500 µT
68
*
69
* Resolution according to datasheet is 0.3µT/LSB
70
*/
71
#define IST8310_RESOLUTION 0.3
72
73
static const int16_t IST8310_MAX_VAL_XY = (1600 / IST8310_RESOLUTION) + 1;
74
static const int16_t IST8310_MIN_VAL_XY = -IST8310_MAX_VAL_XY;
75
static const int16_t IST8310_MAX_VAL_Z = (2500 / IST8310_RESOLUTION) + 1;
76
static const int16_t IST8310_MIN_VAL_Z = -IST8310_MAX_VAL_Z;
77
78
79
extern const AP_HAL::HAL &hal;
80
81
AP_Compass_Backend *AP_Compass_IST8310::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
82
bool force_external,
83
enum Rotation rotation)
84
{
85
if (!dev) {
86
return nullptr;
87
}
88
89
AP_Compass_IST8310 *sensor = NEW_NOTHROW AP_Compass_IST8310(std::move(dev), force_external, rotation);
90
if (!sensor || !sensor->init()) {
91
delete sensor;
92
return nullptr;
93
}
94
95
return sensor;
96
}
97
98
AP_Compass_IST8310::AP_Compass_IST8310(AP_HAL::OwnPtr<AP_HAL::Device> dev,
99
bool force_external,
100
enum Rotation rotation)
101
: _dev(std::move(dev))
102
, _rotation(rotation)
103
, _force_external(force_external)
104
{
105
}
106
107
bool AP_Compass_IST8310::init()
108
{
109
uint8_t reset_count = 0;
110
111
_dev->get_semaphore()->take_blocking();
112
113
// high retries for init
114
_dev->set_retries(10);
115
116
/*
117
unfortunately the IST8310 employs the novel concept of a
118
writeable WHOAMI register. The register can become corrupt due
119
to bus noise, and what is worse it persists the corruption even
120
across a power cycle. If you power it off for 30s or more then
121
it will reset to the default of 0x10, but for less than that the
122
value of WAI is unreliable.
123
124
To avoid this issue we do a reset of the device before we probe
125
the WAI register. This is nasty as we don't yet know we've found
126
a real IST8310, but it is the best we can do given the bad
127
hardware design of the sensor
128
*/
129
_dev->write_register(CNTL2_REG, CNTL2_VAL_SRST);
130
hal.scheduler->delay(10);
131
132
uint8_t whoami;
133
if (!_dev->read_registers(WAI_REG, &whoami, 1) ||
134
whoami != DEVICE_ID) {
135
// not an IST8310
136
goto fail;
137
}
138
139
for (; reset_count < 5; reset_count++) {
140
if (!_dev->write_register(CNTL2_REG, CNTL2_VAL_SRST)) {
141
hal.scheduler->delay(10);
142
continue;
143
}
144
145
hal.scheduler->delay(10);
146
147
uint8_t cntl2 = 0xFF;
148
if (_dev->read_registers(CNTL2_REG, &cntl2, 1) &&
149
(cntl2 & 0x01) == 0) {
150
break;
151
}
152
}
153
154
if (reset_count == 5) {
155
printf("IST8310: failed to reset device\n");
156
goto fail;
157
}
158
159
if (!_dev->write_register(AVGCNTL_REG, AVGCNTL_VAL_Y_16 | AVGCNTL_VAL_XZ_16) ||
160
!_dev->write_register(PDCNTL_REG, PDCNTL_VAL_PULSE_DURATION_NORMAL)) {
161
printf("IST8310: found device but could not set it up\n");
162
goto fail;
163
}
164
165
// lower retries for run
166
_dev->set_retries(3);
167
168
// start state machine: request a sample
169
start_conversion();
170
171
_dev->get_semaphore()->give();
172
173
// register compass instance
174
_dev->set_device_type(DEVTYPE_IST8310);
175
if (!register_compass(_dev->get_bus_id(), _instance)) {
176
return false;
177
}
178
set_dev_id(_instance, _dev->get_bus_id());
179
180
printf("%s found on bus %u id %u address 0x%02x\n", name,
181
_dev->bus_num(), unsigned(_dev->get_bus_id()), _dev->get_bus_address());
182
183
set_rotation(_instance, _rotation);
184
185
if (_force_external) {
186
set_external(_instance, true);
187
}
188
189
_periodic_handle = _dev->register_periodic_callback(SAMPLING_PERIOD_USEC,
190
FUNCTOR_BIND_MEMBER(&AP_Compass_IST8310::timer, void));
191
192
return true;
193
194
fail:
195
_dev->get_semaphore()->give();
196
return false;
197
}
198
199
void AP_Compass_IST8310::start_conversion()
200
{
201
if (!_dev->write_register(CNTL1_REG, CNTL1_VAL_SINGLE_MEASUREMENT_MODE)) {
202
_ignore_next_sample = true;
203
}
204
}
205
206
void AP_Compass_IST8310::timer()
207
{
208
if (_ignore_next_sample) {
209
_ignore_next_sample = false;
210
start_conversion();
211
return;
212
}
213
214
struct PACKED {
215
le16_t rx;
216
le16_t ry;
217
le16_t rz;
218
} buffer;
219
220
bool ret = _dev->read_registers(OUTPUT_X_L_REG, (uint8_t *) &buffer, sizeof(buffer));
221
if (!ret) {
222
return;
223
}
224
225
start_conversion();
226
227
/* same period, but start counting from now */
228
_dev->adjust_periodic_callback(_periodic_handle, SAMPLING_PERIOD_USEC);
229
230
auto x = static_cast<int16_t>(le16toh(buffer.rx));
231
auto y = static_cast<int16_t>(le16toh(buffer.ry));
232
auto z = static_cast<int16_t>(le16toh(buffer.rz));
233
234
/*
235
* Check if value makes sense according to the FSR and Resolution of
236
* this sensor, discarding outliers
237
*/
238
if (x > IST8310_MAX_VAL_XY || x < IST8310_MIN_VAL_XY ||
239
y > IST8310_MAX_VAL_XY || y < IST8310_MIN_VAL_XY ||
240
z > IST8310_MAX_VAL_Z || z < IST8310_MIN_VAL_Z) {
241
return;
242
}
243
244
// flip Z to conform to right-hand rule convention
245
z = -z;
246
247
/* Resolution: 0.3 µT/LSB - already convert to milligauss */
248
Vector3f field = Vector3f{x * 3.0f, y * 3.0f, z * 3.0f};
249
250
accumulate_sample(field, _instance);
251
}
252
253
void AP_Compass_IST8310::read()
254
{
255
drain_accumulated_samples(_instance);
256
}
257
258
#endif // AP_COMPASS_IST8310_ENABLED
259
260