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_LIS3MDL.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
/*
16
Driver by Andrew Tridgell, Nov 2016
17
18
thanks to Robert Dickenson and the PX4 team for register definitions
19
*/
20
#include "AP_Compass_LIS3MDL.h"
21
22
#if AP_COMPASS_LIS3MDL_ENABLED
23
24
#include <AP_HAL/AP_HAL.h>
25
#include <utility>
26
#include <AP_Math/AP_Math.h>
27
#include <stdio.h>
28
29
#define ADDR_CTRL_REG1 0x20
30
#define ADDR_CTRL_REG2 0x21
31
#define ADDR_CTRL_REG3 0x22
32
#define ADDR_CTRL_REG4 0x23
33
#define ADDR_CTRL_REG5 0x24
34
35
#define ADDR_STATUS_REG 0x27
36
#define ADDR_OUT_X_L 0x28
37
#define ADDR_OUT_X_H 0x29
38
#define ADDR_OUT_Y_L 0x2a
39
#define ADDR_OUT_Y_H 0x2b
40
#define ADDR_OUT_Z_L 0x2c
41
#define ADDR_OUT_Z_H 0x2d
42
#define ADDR_OUT_T_L 0x2e
43
#define ADDR_OUT_T_H 0x2f
44
45
#define MODE_REG_CONTINOUS_MODE (0 << 0)
46
#define MODE_REG_SINGLE_MODE (1 << 0)
47
48
#define ADDR_WHO_AM_I 0x0f
49
#define ID_WHO_AM_I 0x3d
50
51
extern const AP_HAL::HAL &hal;
52
53
AP_Compass_Backend *AP_Compass_LIS3MDL::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
54
bool force_external,
55
enum Rotation rotation)
56
{
57
if (!dev) {
58
return nullptr;
59
}
60
AP_Compass_LIS3MDL *sensor = NEW_NOTHROW AP_Compass_LIS3MDL(std::move(dev), force_external, rotation);
61
if (!sensor || !sensor->init()) {
62
delete sensor;
63
return nullptr;
64
}
65
66
return sensor;
67
}
68
69
AP_Compass_LIS3MDL::AP_Compass_LIS3MDL(AP_HAL::OwnPtr<AP_HAL::Device> _dev,
70
bool _force_external,
71
enum Rotation _rotation)
72
: dev(std::move(_dev))
73
, force_external(_force_external)
74
, rotation(_rotation)
75
{
76
}
77
78
bool AP_Compass_LIS3MDL::init()
79
{
80
dev->get_semaphore()->take_blocking();
81
82
if (dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
83
dev->set_read_flag(0xC0);
84
}
85
86
// high retries for init
87
dev->set_retries(10);
88
89
uint8_t whoami;
90
if (!dev->read_registers(ADDR_WHO_AM_I, &whoami, 1) ||
91
whoami != ID_WHO_AM_I) {
92
// not a 3MDL
93
goto fail;
94
}
95
96
dev->setup_checked_registers(5);
97
98
dev->write_register(ADDR_CTRL_REG1, 0xFC, true); // 80Hz, UHP
99
dev->write_register(ADDR_CTRL_REG2, 0, true); // 4Ga range
100
dev->write_register(ADDR_CTRL_REG3, 0, true); // continuous
101
dev->write_register(ADDR_CTRL_REG4, 0x0C, true); // z-axis ultra high perf
102
dev->write_register(ADDR_CTRL_REG5, 0x40, true); // block-data-update
103
104
// lower retries for run
105
dev->set_retries(3);
106
107
dev->get_semaphore()->give();
108
109
/* register the compass instance in the frontend */
110
dev->set_device_type(DEVTYPE_LIS3MDL);
111
if (!register_compass(dev->get_bus_id(), compass_instance)) {
112
return false;
113
}
114
set_dev_id(compass_instance, dev->get_bus_id());
115
116
printf("Found a LIS3MDL on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), compass_instance);
117
118
set_rotation(compass_instance, rotation);
119
120
if (force_external) {
121
set_external(compass_instance, true);
122
}
123
124
// call timer() at 80Hz
125
dev->register_periodic_callback(1000000U/80U,
126
FUNCTOR_BIND_MEMBER(&AP_Compass_LIS3MDL::timer, void));
127
128
return true;
129
130
fail:
131
dev->get_semaphore()->give();
132
return false;
133
}
134
135
void AP_Compass_LIS3MDL::timer()
136
{
137
struct PACKED {
138
int16_t magx;
139
int16_t magy;
140
int16_t magz;
141
} data;
142
const float range_scale = 1000.0f / 6842.0f;
143
144
// check data ready
145
uint8_t status;
146
if (!dev->read_registers(ADDR_STATUS_REG, (uint8_t *)&status, 1)) {
147
goto check_registers;
148
}
149
if (!(status & 0x08)) {
150
// data not available yet
151
goto check_registers;
152
}
153
154
if (!dev->read_registers(ADDR_OUT_X_L, (uint8_t *)&data, sizeof(data))) {
155
goto check_registers;
156
}
157
158
{
159
Vector3f field{
160
data.magx * range_scale,
161
data.magy * range_scale,
162
data.magz * range_scale,
163
};
164
165
accumulate_sample(field, compass_instance);
166
}
167
168
check_registers:
169
dev->check_next_register();
170
}
171
172
void AP_Compass_LIS3MDL::read()
173
{
174
drain_accumulated_samples(compass_instance);
175
}
176
177
#endif // AP_COMPASS_LIS3MDL_ENABLED
178
179