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_LSM303D.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
#include "AP_Compass_LSM303D.h"
17
18
#if AP_COMPASS_LSM303D_ENABLED
19
20
#include <utility>
21
22
#include <AP_HAL/AP_HAL.h>
23
#include <AP_Math/AP_Math.h>
24
25
extern const AP_HAL::HAL &hal;
26
27
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
28
#include <AP_HAL_Linux/GPIO.h>
29
#endif
30
31
#ifndef LSM303D_DRDY_M_PIN
32
#define LSM303D_DRDY_M_PIN -1
33
#endif
34
35
/* SPI protocol address bits */
36
#define DIR_READ (1<<7)
37
#define DIR_WRITE (0<<7)
38
#define ADDR_INCREMENT (1<<6)
39
40
/* register addresses: A: accel, M: mag, T: temp */
41
#define ADDR_WHO_AM_I 0x0F
42
#define WHO_I_AM 0x49
43
44
#define ADDR_OUT_TEMP_L 0x05
45
#define ADDR_OUT_TEMP_H 0x06
46
#define ADDR_STATUS_M 0x07
47
#define ADDR_OUT_X_L_M 0x08
48
#define ADDR_OUT_X_H_M 0x09
49
#define ADDR_OUT_Y_L_M 0x0A
50
#define ADDR_OUT_Y_H_M 0x0B
51
#define ADDR_OUT_Z_L_M 0x0C
52
#define ADDR_OUT_Z_H_M 0x0D
53
54
#define ADDR_INT_CTRL_M 0x12
55
#define ADDR_INT_SRC_M 0x13
56
#define ADDR_REFERENCE_X 0x1c
57
#define ADDR_REFERENCE_Y 0x1d
58
#define ADDR_REFERENCE_Z 0x1e
59
60
#define ADDR_STATUS_A 0x27
61
#define ADDR_OUT_X_L_A 0x28
62
#define ADDR_OUT_X_H_A 0x29
63
#define ADDR_OUT_Y_L_A 0x2A
64
#define ADDR_OUT_Y_H_A 0x2B
65
#define ADDR_OUT_Z_L_A 0x2C
66
#define ADDR_OUT_Z_H_A 0x2D
67
68
#define ADDR_CTRL_REG0 0x1F
69
#define ADDR_CTRL_REG1 0x20
70
#define ADDR_CTRL_REG2 0x21
71
#define ADDR_CTRL_REG3 0x22
72
#define ADDR_CTRL_REG4 0x23
73
#define ADDR_CTRL_REG5 0x24
74
#define ADDR_CTRL_REG6 0x25
75
#define ADDR_CTRL_REG7 0x26
76
77
#define ADDR_FIFO_CTRL 0x2e
78
#define ADDR_FIFO_SRC 0x2f
79
80
#define ADDR_IG_CFG1 0x30
81
#define ADDR_IG_SRC1 0x31
82
#define ADDR_IG_THS1 0x32
83
#define ADDR_IG_DUR1 0x33
84
#define ADDR_IG_CFG2 0x34
85
#define ADDR_IG_SRC2 0x35
86
#define ADDR_IG_THS2 0x36
87
#define ADDR_IG_DUR2 0x37
88
#define ADDR_CLICK_CFG 0x38
89
#define ADDR_CLICK_SRC 0x39
90
#define ADDR_CLICK_THS 0x3a
91
#define ADDR_TIME_LIMIT 0x3b
92
#define ADDR_TIME_LATENCY 0x3c
93
#define ADDR_TIME_WINDOW 0x3d
94
#define ADDR_ACT_THS 0x3e
95
#define ADDR_ACT_DUR 0x3f
96
97
#define REG1_RATE_BITS_A ((1<<7) | (1<<6) | (1<<5) | (1<<4))
98
#define REG1_POWERDOWN_A ((0<<7) | (0<<6) | (0<<5) | (0<<4))
99
#define REG1_RATE_3_125HZ_A ((0<<7) | (0<<6) | (0<<5) | (1<<4))
100
#define REG1_RATE_6_25HZ_A ((0<<7) | (0<<6) | (1<<5) | (0<<4))
101
#define REG1_RATE_12_5HZ_A ((0<<7) | (0<<6) | (1<<5) | (1<<4))
102
#define REG1_RATE_25HZ_A ((0<<7) | (1<<6) | (0<<5) | (0<<4))
103
#define REG1_RATE_50HZ_A ((0<<7) | (1<<6) | (0<<5) | (1<<4))
104
#define REG1_RATE_100HZ_A ((0<<7) | (1<<6) | (1<<5) | (0<<4))
105
#define REG1_RATE_200HZ_A ((0<<7) | (1<<6) | (1<<5) | (1<<4))
106
#define REG1_RATE_400HZ_A ((1<<7) | (0<<6) | (0<<5) | (0<<4))
107
#define REG1_RATE_800HZ_A ((1<<7) | (0<<6) | (0<<5) | (1<<4))
108
#define REG1_RATE_1600HZ_A ((1<<7) | (0<<6) | (1<<5) | (0<<4))
109
110
#define REG1_BDU_UPDATE (1<<3)
111
#define REG1_Z_ENABLE_A (1<<2)
112
#define REG1_Y_ENABLE_A (1<<1)
113
#define REG1_X_ENABLE_A (1<<0)
114
115
#define REG2_ANTIALIAS_FILTER_BW_BITS_A ((1<<7) | (1<<6))
116
#define REG2_AA_FILTER_BW_773HZ_A ((0<<7) | (0<<6))
117
#define REG2_AA_FILTER_BW_194HZ_A ((0<<7) | (1<<6))
118
#define REG2_AA_FILTER_BW_362HZ_A ((1<<7) | (0<<6))
119
#define REG2_AA_FILTER_BW_50HZ_A ((1<<7) | (1<<6))
120
121
#define REG2_FULL_SCALE_BITS_A ((1<<5) | (1<<4) | (1<<3))
122
#define REG2_FULL_SCALE_2G_A ((0<<5) | (0<<4) | (0<<3))
123
#define REG2_FULL_SCALE_4G_A ((0<<5) | (0<<4) | (1<<3))
124
#define REG2_FULL_SCALE_6G_A ((0<<5) | (1<<4) | (0<<3))
125
#define REG2_FULL_SCALE_8G_A ((0<<5) | (1<<4) | (1<<3))
126
#define REG2_FULL_SCALE_16G_A ((1<<5) | (0<<4) | (0<<3))
127
128
#define REG5_ENABLE_T (1<<7)
129
130
#define REG5_RES_HIGH_M ((1<<6) | (1<<5) | (1<<7))
131
#define REG5_RES_LOW_M ((0<<6) | (0<<5))
132
133
#define REG5_RATE_BITS_M ((1<<4) | (1<<3) | (1<<2))
134
#define REG5_RATE_3_125HZ_M ((0<<4) | (0<<3) | (0<<2))
135
#define REG5_RATE_6_25HZ_M ((0<<4) | (0<<3) | (1<<2))
136
#define REG5_RATE_12_5HZ_M ((0<<4) | (1<<3) | (0<<2))
137
#define REG5_RATE_25HZ_M ((0<<4) | (1<<3) | (1<<2))
138
#define REG5_RATE_50HZ_M ((1<<4) | (0<<3) | (0<<2))
139
#define REG5_RATE_100HZ_M ((1<<4) | (0<<3) | (1<<2))
140
#define REG5_RATE_DO_NOT_USE_M ((1<<4) | (1<<3) | (0<<2))
141
142
#define REG6_FULL_SCALE_BITS_M ((1<<6) | (1<<5))
143
#define REG6_FULL_SCALE_2GA_M ((0<<6) | (0<<5))
144
#define REG6_FULL_SCALE_4GA_M ((0<<6) | (1<<5))
145
#define REG6_FULL_SCALE_8GA_M ((1<<6) | (0<<5))
146
#define REG6_FULL_SCALE_12GA_M ((1<<6) | (1<<5))
147
148
#define REG7_CONT_MODE_M ((0<<1) | (0<<0))
149
150
#define INT_CTRL_M 0x12
151
#define INT_SRC_M 0x13
152
153
#define LSM303D_MAG_DEFAULT_RANGE_GA 2
154
#define LSM303D_MAG_DEFAULT_RATE 100
155
156
AP_Compass_LSM303D::AP_Compass_LSM303D(AP_HAL::OwnPtr<AP_HAL::Device> dev)
157
: _dev(std::move(dev))
158
{
159
}
160
161
AP_Compass_Backend *AP_Compass_LSM303D::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
162
enum Rotation rotation)
163
{
164
if (!dev) {
165
return nullptr;
166
}
167
AP_Compass_LSM303D *sensor = NEW_NOTHROW AP_Compass_LSM303D(std::move(dev));
168
if (!sensor || !sensor->init(rotation)) {
169
delete sensor;
170
return nullptr;
171
}
172
173
return sensor;
174
}
175
176
uint8_t AP_Compass_LSM303D::_register_read(uint8_t reg)
177
{
178
uint8_t val = 0;
179
180
reg |= DIR_READ;
181
_dev->read_registers(reg, &val, 1);
182
183
return val;
184
}
185
186
bool AP_Compass_LSM303D::_block_read(uint8_t reg, uint8_t *buf, uint32_t size)
187
{
188
reg |= DIR_READ | ADDR_INCREMENT;
189
return _dev->read_registers(reg, buf, size);
190
}
191
192
void AP_Compass_LSM303D::_register_write(uint8_t reg, uint8_t val)
193
{
194
_dev->write_register(reg, val);
195
}
196
197
void AP_Compass_LSM303D::_register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits)
198
{
199
uint8_t val;
200
201
val = _register_read(reg);
202
val &= ~clearbits;
203
val |= setbits;
204
_register_write(reg, val);
205
}
206
207
/**
208
* Return true if the LSM303D has new data available for both the mag and
209
* the accels.
210
*/
211
bool AP_Compass_LSM303D::_data_ready()
212
{
213
return _drdy_pin_m == nullptr || (_drdy_pin_m->read() != 0);
214
}
215
216
217
// Read Sensor data
218
bool AP_Compass_LSM303D::_read_sample()
219
{
220
struct PACKED {
221
uint8_t status;
222
int16_t x;
223
int16_t y;
224
int16_t z;
225
} rx;
226
227
if (_register_read(ADDR_CTRL_REG7) != _reg7_expected) {
228
DEV_PRINTF("LSM303D _read_data_transaction_accel: _reg7_expected unexpected\n");
229
return false;
230
}
231
232
if (!_data_ready()) {
233
return false;
234
}
235
236
if (!_block_read(ADDR_STATUS_M, (uint8_t *) &rx, sizeof(rx))) {
237
return false;
238
}
239
240
/* check for overrun */
241
if ((rx.status & 0x70) != 0) {
242
return false;
243
}
244
245
if (rx.x == 0 && rx.y == 0 && rx.z == 0) {
246
return false;
247
}
248
249
_mag_x = rx.x;
250
_mag_y = rx.y;
251
_mag_z = rx.z;
252
253
return true;
254
}
255
256
bool AP_Compass_LSM303D::init(enum Rotation rotation)
257
{
258
if (LSM303D_DRDY_M_PIN >= 0) {
259
_drdy_pin_m = hal.gpio->channel(LSM303D_DRDY_M_PIN);
260
_drdy_pin_m->mode(HAL_GPIO_INPUT);
261
}
262
263
bool success = _hardware_init();
264
265
if (!success) {
266
return false;
267
}
268
269
_initialised = true;
270
271
/* register the compass instance in the frontend */
272
_dev->set_device_type(DEVTYPE_LSM303D);
273
if (!register_compass(_dev->get_bus_id(), _compass_instance)) {
274
return false;
275
}
276
set_dev_id(_compass_instance, _dev->get_bus_id());
277
278
set_rotation(_compass_instance, rotation);
279
280
// read at 91Hz. We don't run at 100Hz as fetching data too fast can cause some very
281
// odd periodic changes in the output data
282
_dev->register_periodic_callback(11000, FUNCTOR_BIND_MEMBER(&AP_Compass_LSM303D::_update, void));
283
284
return true;
285
}
286
287
bool AP_Compass_LSM303D::_hardware_init()
288
{
289
_dev->get_semaphore()->take_blocking();
290
291
// initially run the bus at low speed
292
_dev->set_speed(AP_HAL::Device::SPEED_LOW);
293
294
// Test WHOAMI
295
uint8_t whoami = _register_read(ADDR_WHO_AM_I);
296
if (whoami != WHO_I_AM) {
297
goto fail_whoami;
298
}
299
300
uint8_t tries;
301
for (tries = 0; tries < 5; tries++) {
302
// ensure the chip doesn't interpret any other bus traffic as I2C
303
_disable_i2c();
304
305
/* enable mag */
306
_reg7_expected = REG7_CONT_MODE_M;
307
_register_write(ADDR_CTRL_REG7, _reg7_expected);
308
_register_write(ADDR_CTRL_REG5, REG5_RES_HIGH_M);
309
310
// DRDY on MAG on INT2
311
_register_write(ADDR_CTRL_REG4, 0x04);
312
313
_mag_set_range(LSM303D_MAG_DEFAULT_RANGE_GA);
314
_mag_set_samplerate(LSM303D_MAG_DEFAULT_RATE);
315
316
hal.scheduler->delay(10);
317
if (_data_ready()) {
318
break;
319
}
320
}
321
if (tries == 5) {
322
DEV_PRINTF("Failed to boot LSM303D 5 times\n");
323
goto fail_tries;
324
}
325
326
_dev->set_speed(AP_HAL::Device::SPEED_HIGH);
327
_dev->get_semaphore()->give();
328
329
return true;
330
331
fail_tries:
332
fail_whoami:
333
_dev->get_semaphore()->give();
334
_dev->set_speed(AP_HAL::Device::SPEED_HIGH);
335
return false;
336
}
337
338
void AP_Compass_LSM303D::_update()
339
{
340
if (!_read_sample()) {
341
return;
342
}
343
344
Vector3f raw_field = Vector3f(_mag_x, _mag_y, _mag_z) * _mag_range_scale;
345
346
accumulate_sample(raw_field, _compass_instance, 10);
347
}
348
349
// Read Sensor data
350
void AP_Compass_LSM303D::read()
351
{
352
if (!_initialised) {
353
return;
354
}
355
356
drain_accumulated_samples(_compass_instance);
357
}
358
359
void AP_Compass_LSM303D::_disable_i2c()
360
{
361
// TODO: use the register names
362
uint8_t a = _register_read(0x02);
363
_register_write(0x02, (0x10 | a));
364
a = _register_read(0x02);
365
_register_write(0x02, (0xF7 & a));
366
a = _register_read(0x15);
367
_register_write(0x15, (0x80 | a));
368
a = _register_read(0x02);
369
_register_write(0x02, (0xE7 & a));
370
}
371
372
bool AP_Compass_LSM303D::_mag_set_range(uint8_t max_ga)
373
{
374
uint8_t setbits = 0;
375
uint8_t clearbits = REG6_FULL_SCALE_BITS_M;
376
float new_scale_ga_digit = 0.0f;
377
378
if (max_ga == 0) {
379
max_ga = 12;
380
}
381
382
if (max_ga <= 2) {
383
_mag_range_ga = 2;
384
setbits |= REG6_FULL_SCALE_2GA_M;
385
new_scale_ga_digit = 0.080f;
386
} else if (max_ga <= 4) {
387
_mag_range_ga = 4;
388
setbits |= REG6_FULL_SCALE_4GA_M;
389
new_scale_ga_digit = 0.160f;
390
} else if (max_ga <= 8) {
391
_mag_range_ga = 8;
392
setbits |= REG6_FULL_SCALE_8GA_M;
393
new_scale_ga_digit = 0.320f;
394
} else if (max_ga <= 12) {
395
_mag_range_ga = 12;
396
setbits |= REG6_FULL_SCALE_12GA_M;
397
new_scale_ga_digit = 0.479f;
398
} else {
399
return false;
400
}
401
402
_mag_range_scale = new_scale_ga_digit;
403
_register_modify(ADDR_CTRL_REG6, clearbits, setbits);
404
405
return true;
406
}
407
408
bool AP_Compass_LSM303D::_mag_set_samplerate(uint16_t frequency)
409
{
410
uint8_t setbits = 0;
411
uint8_t clearbits = REG5_RATE_BITS_M;
412
413
if (frequency == 0) {
414
frequency = 100;
415
}
416
417
if (frequency <= 25) {
418
setbits |= REG5_RATE_25HZ_M;
419
_mag_samplerate = 25;
420
} else if (frequency <= 50) {
421
setbits |= REG5_RATE_50HZ_M;
422
_mag_samplerate = 50;
423
} else if (frequency <= 100) {
424
setbits |= REG5_RATE_100HZ_M;
425
_mag_samplerate = 100;
426
} else {
427
return false;
428
}
429
430
_register_modify(ADDR_CTRL_REG5, clearbits, setbits);
431
432
return true;
433
}
434
435
#endif // AP_COMPASS_LSM303D_ENABLED
436
437