Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/AP_Compass_LIS2MDL.cpp
6351 views
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 for the LIS2MDL magnetometer.
17
*/
18
#include "AP_Compass_config.h"
19
20
#if AP_COMPASS_LIS2MDL_ENABLED
21
22
#include "AP_Compass_LIS2MDL.h"
23
24
#include <AP_HAL/AP_HAL.h>
25
#include <utility>
26
#include <AP_Math/AP_Math.h>
27
#include <stdio.h>
28
29
// Register addresses
30
#define ADDR_WHO_AM_I 0x4F
31
#define ADDR_CFG_REG_A 0x60
32
#define ADDR_CFG_REG_B 0x61
33
#define ADDR_CFG_REG_C 0x62
34
#define ADDR_STATUS_REG 0x67
35
#define ADDR_OUT_X_L 0x68
36
37
// WHO_AM_I device ID
38
#define ID_WHO_AM_I 0x40
39
40
AP_Compass_Backend *AP_Compass_LIS2MDL::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
41
bool force_external,
42
enum Rotation rotation)
43
{
44
if (!dev) {
45
return nullptr;
46
}
47
AP_Compass_LIS2MDL *sensor = NEW_NOTHROW AP_Compass_LIS2MDL(std::move(dev), force_external, rotation);
48
if (!sensor || !sensor->init()) {
49
delete sensor;
50
return nullptr;
51
}
52
53
return sensor;
54
}
55
56
AP_Compass_LIS2MDL::AP_Compass_LIS2MDL(AP_HAL::OwnPtr<AP_HAL::Device> _dev,
57
bool _force_external,
58
enum Rotation _rotation)
59
: dev(std::move(_dev))
60
, force_external(_force_external)
61
, rotation(_rotation)
62
{
63
}
64
65
// @brief Initialize the sensor
66
bool AP_Compass_LIS2MDL::init()
67
{
68
WITH_SEMAPHORE(dev->get_semaphore());
69
70
if (dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
71
// LIS2MDL SPI reads are MSb=1, autoincrement.
72
dev->set_read_flag(0xC0);
73
}
74
75
// high retries for init
76
dev->set_retries(10);
77
78
uint8_t whoami;
79
if (!dev->read_registers(ADDR_WHO_AM_I, &whoami, 1) ||
80
whoami != ID_WHO_AM_I) {
81
// not a LIS2MDL
82
return false;
83
}
84
85
dev->setup_checked_registers(3);
86
87
// Configure for 100Hz continuous mode, with temperature compensation.
88
dev->write_register(ADDR_CFG_REG_A, 0b10001100, true); // ODR=100Hz, continuous mode, temp comp on
89
90
// Default settings for CFG_REG_B are fine.
91
dev->write_register(ADDR_CFG_REG_B, 0x00, true);
92
93
// Enable Block Data Update (BDU)
94
dev->write_register(ADDR_CFG_REG_C, 0b00010000, true);
95
96
// lower retries for run
97
dev->set_retries(3);
98
99
/* register the compass instance in the frontend */
100
dev->set_device_type(DEVTYPE_LIS2MDL);
101
if (!register_compass(dev->get_bus_id())) {
102
return false;
103
}
104
105
printf("Found a LIS2MDL on 0x%x as compass %u\n", unsigned(dev->get_bus_id()), instance);
106
107
set_rotation(rotation);
108
109
if (force_external) {
110
set_external(force_external);
111
}
112
113
// call timer() at 100Hz
114
dev->register_periodic_callback(1000000U/100U,
115
FUNCTOR_BIND_MEMBER(&AP_Compass_LIS2MDL::timer, void));
116
117
return true;
118
}
119
120
// @brief Read data from the sensor and accumulate it
121
void AP_Compass_LIS2MDL::timer()
122
{
123
struct PACKED {
124
int16_t magx;
125
int16_t magy;
126
int16_t magz;
127
} data;
128
129
// Sensitivity is 1.5 mgauss/LSB
130
const float range_scale = 1.5f;
131
132
// check data ready
133
uint8_t status;
134
if (!dev->read_registers(ADDR_STATUS_REG, &status, 1)) {
135
goto check_registers;
136
}
137
if (!(status & 0x08)) { // ZYXDA bit
138
// data not available yet
139
goto check_registers;
140
}
141
142
if (!dev->read_registers(ADDR_OUT_X_L, (uint8_t *)&data, sizeof(data))) {
143
goto check_registers;
144
}
145
146
{
147
Vector3f field{
148
(float)data.magx * range_scale,
149
(float)data.magy * range_scale,
150
(float)-data.magz * range_scale, // for unknown reasons the Z axis appears to be reversed, without this it is impossible to orient correctly
151
};
152
153
accumulate_sample(field, instance);
154
}
155
156
check_registers:
157
dev->check_next_register();
158
}
159
160
// @brief Publish accumulated data to the frontend
161
void AP_Compass_LIS2MDL::read()
162
{
163
drain_accumulated_samples();
164
}
165
166
#endif // AP_COMPASS_LIS2MDL_ENABLED
167
168