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_Backend.cpp
Views: 1798
1
#include "AP_Compass_config.h"
2
3
#if AP_COMPASS_ENABLED
4
5
#include <AP_HAL/AP_HAL.h>
6
7
#include "AP_Compass.h"
8
#include "AP_Compass_Backend.h"
9
10
#include <AP_BattMonitor/AP_BattMonitor.h>
11
#include <AP_Vehicle/AP_Vehicle_Type.h>
12
#include <AP_BoardConfig/AP_BoardConfig.h>
13
14
extern const AP_HAL::HAL& hal;
15
16
AP_Compass_Backend::AP_Compass_Backend()
17
: _compass(AP::compass())
18
{
19
}
20
21
void AP_Compass_Backend::rotate_field(Vector3f &mag, uint8_t instance)
22
{
23
Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];
24
if (MAG_BOARD_ORIENTATION != ROTATION_NONE) {
25
mag.rotate(MAG_BOARD_ORIENTATION);
26
}
27
mag.rotate(state.rotation);
28
29
#ifdef HAL_HEATER_MAG_OFFSET
30
/*
31
apply compass compensations for boards that have a heater which
32
interferes with an internal compass. This needs to be applied
33
before the board orientation so it is independent of
34
AHRS_ORIENTATION
35
*/
36
if (!is_external(instance)) {
37
const uint32_t dev_id = uint32_t(_compass._state[Compass::StateIndex(instance)].dev_id);
38
static const struct offset {
39
uint32_t dev_id;
40
Vector3f ofs;
41
} offsets[] = HAL_HEATER_MAG_OFFSET;
42
const auto *bc = AP::boardConfig();
43
if (bc) {
44
for (const auto &o : offsets) {
45
if (o.dev_id == dev_id) {
46
mag += o.ofs * bc->get_heater_duty_cycle() * 0.01;
47
}
48
}
49
}
50
}
51
#endif
52
53
if (!state.external) {
54
mag.rotate(_compass._board_orientation);
55
} else {
56
// add user selectable orientation
57
mag.rotate((enum Rotation)state.orientation.get());
58
}
59
}
60
61
void AP_Compass_Backend::publish_raw_field(const Vector3f &mag, uint8_t instance)
62
{
63
// note that we do not set last_update_usec here as otherwise the
64
// EKF and DCM would end up consuming compass data at the full
65
// sensor rate. We want them to consume only the filtered fields
66
#if COMPASS_CAL_ENABLED
67
auto& cal = _compass._calibrator[_compass._get_priority(Compass::StateIndex(instance))];
68
if (cal != nullptr) {
69
Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];
70
state.last_update_ms = AP_HAL::millis();
71
cal->new_sample(mag);
72
}
73
#endif
74
}
75
76
void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i)
77
{
78
Compass::mag_state &state = _compass._state[Compass::StateIndex(i)];
79
80
const Vector3f &offsets = state.offset.get();
81
#if AP_COMPASS_DIAGONALS_ENABLED
82
const Vector3f &diagonals = state.diagonals.get();
83
const Vector3f &offdiagonals = state.offdiagonals.get();
84
#endif
85
86
// add in the basic offsets
87
mag += offsets;
88
89
// add in scale factor, use a wide sanity check. The calibrator
90
// uses a narrower check.
91
if (_compass.have_scale_factor(i)) {
92
mag *= state.scale_factor;
93
}
94
95
#if AP_COMPASS_DIAGONALS_ENABLED
96
// apply elliptical correction
97
if (!diagonals.is_zero()) {
98
Matrix3f mat(
99
diagonals.x, offdiagonals.x, offdiagonals.y,
100
offdiagonals.x, diagonals.y, offdiagonals.z,
101
offdiagonals.y, offdiagonals.z, diagonals.z
102
);
103
104
mag = mat * mag;
105
}
106
#endif
107
108
#if COMPASS_MOT_ENABLED
109
const Vector3f &mot = state.motor_compensation.get();
110
/*
111
calculate motor-power based compensation
112
note that _motor_offset[] is kept even if compensation is not
113
being applied so it can be logged correctly
114
*/
115
state.motor_offset.zero();
116
if (_compass._per_motor.enabled() && i == 0) {
117
// per-motor correction is only valid for first compass
118
_compass._per_motor.compensate(state.motor_offset);
119
} else if (_compass._motor_comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {
120
state.motor_offset = mot * _compass._thr;
121
} else if (_compass._motor_comp_type == AP_COMPASS_MOT_COMP_CURRENT) {
122
AP_BattMonitor &battery = AP::battery();
123
float current;
124
if (battery.current_amps(current)) {
125
state.motor_offset = mot * current;
126
}
127
}
128
129
/*
130
we apply the motor offsets after we apply the elliptical
131
correction. This is needed to match the way that the motor
132
compensation values are calculated, as they are calculated based
133
on final field outputs, not on the raw outputs
134
*/
135
mag += state.motor_offset;
136
#endif // COMPASS_MOT_ENABLED
137
}
138
139
void AP_Compass_Backend::accumulate_sample(Vector3f &field, uint8_t instance,
140
uint32_t max_samples)
141
{
142
/* rotate raw_field from sensor frame to body frame */
143
rotate_field(field, instance);
144
145
/* publish raw_field (uncorrected point sample) for calibration use */
146
publish_raw_field(field, instance);
147
148
/* correct raw_field for known errors */
149
correct_field(field, instance);
150
151
if (!field_ok(field)) {
152
return;
153
}
154
155
WITH_SEMAPHORE(_sem);
156
157
Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];
158
state.accum += field;
159
state.accum_count++;
160
if (max_samples && state.accum_count >= max_samples) {
161
state.accum_count /= 2;
162
state.accum /= 2;
163
}
164
}
165
166
void AP_Compass_Backend::drain_accumulated_samples(uint8_t instance,
167
const Vector3f *scaling)
168
{
169
WITH_SEMAPHORE(_sem);
170
171
Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];
172
173
if (state.accum_count == 0) {
174
return;
175
}
176
177
if (scaling) {
178
state.accum *= *scaling;
179
}
180
state.accum /= state.accum_count;
181
182
publish_filtered_field(state.accum, instance);
183
184
state.accum.zero();
185
state.accum_count = 0;
186
}
187
188
/*
189
copy latest data to the frontend from a backend
190
*/
191
void AP_Compass_Backend::publish_filtered_field(const Vector3f &mag, uint8_t instance)
192
{
193
Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];
194
195
state.field = mag;
196
197
state.last_update_ms = AP_HAL::millis();
198
state.last_update_usec = AP_HAL::micros();
199
}
200
201
void AP_Compass_Backend::set_last_update_usec(uint32_t last_update, uint8_t instance)
202
{
203
Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];
204
state.last_update_usec = last_update;
205
}
206
207
/*
208
register a new backend with frontend, returning instance which
209
should be used in publish_field()
210
*/
211
bool AP_Compass_Backend::register_compass(int32_t dev_id, uint8_t& instance) const
212
{
213
return _compass.register_compass(dev_id, instance);
214
}
215
216
217
/*
218
set dev_id for an instance
219
*/
220
void AP_Compass_Backend::set_dev_id(uint8_t instance, uint32_t dev_id)
221
{
222
_compass._state[Compass::StateIndex(instance)].dev_id.set_and_notify(dev_id);
223
_compass._state[Compass::StateIndex(instance)].detected_dev_id = dev_id;
224
}
225
226
/*
227
save dev_id, used by SITL
228
*/
229
void AP_Compass_Backend::save_dev_id(uint8_t instance)
230
{
231
_compass._state[Compass::StateIndex(instance)].dev_id.save();
232
}
233
234
/*
235
set external for an instance
236
*/
237
void AP_Compass_Backend::set_external(uint8_t instance, bool external)
238
{
239
if (_compass._state[Compass::StateIndex(instance)].external != 2) {
240
_compass._state[Compass::StateIndex(instance)].external.set_and_notify(external);
241
}
242
}
243
244
bool AP_Compass_Backend::is_external(uint8_t instance)
245
{
246
return _compass._state[Compass::StateIndex(instance)].external;
247
}
248
249
// set rotation of an instance
250
void AP_Compass_Backend::set_rotation(uint8_t instance, enum Rotation rotation)
251
{
252
_compass._state[Compass::StateIndex(instance)].rotation = rotation;
253
}
254
255
static constexpr float FILTER_KOEF = 0.1f;
256
257
/* Check that the compass value is valid by using a mean filter. If
258
* the value is further than filter_range from mean value, it is
259
* rejected.
260
*/
261
bool AP_Compass_Backend::field_ok(const Vector3f &field)
262
{
263
264
265
if (field.is_inf() || field.is_nan()) {
266
return false;
267
}
268
269
const float range = (float)_compass.get_filter_range();
270
if (range <= 0) {
271
return true;
272
}
273
274
const float length = field.length();
275
276
if (is_zero(_mean_field_length)) {
277
_mean_field_length = length;
278
return true;
279
}
280
281
bool ret = true;
282
const float d = fabsf(_mean_field_length - length) / (_mean_field_length + length); // diff divide by mean value in percent ( with the *200.0f on later line)
283
float koeff = FILTER_KOEF;
284
285
if (d * 200.0f > range) { // check the difference from mean value outside allowed range
286
// printf("\nCompass field length error: mean %f got %f\n", (double)_mean_field_length, (double)length );
287
ret = false;
288
koeff /= (d * 10.0f); // 2.5 and more, so one bad sample never change mean more than 4%
289
_error_count++;
290
}
291
_mean_field_length = _mean_field_length * (1 - koeff) + length * koeff; // complimentary filter 1/k
292
293
return ret;
294
}
295
296
297
enum Rotation AP_Compass_Backend::get_board_orientation(void) const
298
{
299
return _compass._board_orientation;
300
}
301
302
#endif // AP_COMPASS_ENABLED
303
304