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.cpp
Views: 1798
1
#include "AP_Compass_config.h"
2
3
#if AP_COMPASS_ENABLED
4
5
#include <AP_HAL/AP_HAL.h>
6
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
7
#include <AP_HAL_Linux/I2CDevice.h>
8
#endif
9
#include <AP_Vehicle/AP_Vehicle_Type.h>
10
#include <AP_BoardConfig/AP_BoardConfig.h>
11
#include <AP_Logger/AP_Logger.h>
12
#include <AP_Vehicle/AP_Vehicle_Type.h>
13
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
14
#include <AP_CustomRotations/AP_CustomRotations.h>
15
#include <GCS_MAVLink/GCS.h>
16
#include <AP_AHRS/AP_AHRS.h>
17
18
#include "AP_Compass_config.h"
19
20
#include "AP_Compass_SITL.h"
21
#include "AP_Compass_AK8963.h"
22
#include "AP_Compass_Backend.h"
23
#include "AP_Compass_BMM150.h"
24
#include "AP_Compass_BMM350.h"
25
#include "AP_Compass_HMC5843.h"
26
#include "AP_Compass_IIS2MDC.h"
27
#include "AP_Compass_IST8308.h"
28
#include "AP_Compass_IST8310.h"
29
#include "AP_Compass_LSM303D.h"
30
#include "AP_Compass_LSM9DS1.h"
31
#include "AP_Compass_LIS3MDL.h"
32
#include "AP_Compass_AK09916.h"
33
#include "AP_Compass_QMC5883L.h"
34
#if AP_COMPASS_DRONECAN_ENABLED
35
#include "AP_Compass_DroneCAN.h"
36
#endif
37
#include "AP_Compass_QMC5883P.h"
38
#include "AP_Compass_MMC3416.h"
39
#include "AP_Compass_MMC5xx3.h"
40
#include "AP_Compass_MAG3110.h"
41
#include "AP_Compass_RM3100.h"
42
#if AP_COMPASS_MSP_ENABLED
43
#include "AP_Compass_MSP.h"
44
#endif
45
#if AP_COMPASS_EXTERNALAHRS_ENABLED
46
#include "AP_Compass_ExternalAHRS.h"
47
#endif
48
#include "AP_Compass.h"
49
#include "Compass_learn.h"
50
#include <stdio.h>
51
52
extern const AP_HAL::HAL& hal;
53
54
#ifndef AP_COMPASS_ENABLE_DEFAULT
55
#define AP_COMPASS_ENABLE_DEFAULT 1
56
#endif
57
58
#ifndef COMPASS_LEARN_DEFAULT
59
#define COMPASS_LEARN_DEFAULT Compass::LEARN_NONE
60
#endif
61
62
#ifndef AP_COMPASS_OFFSETS_MAX_DEFAULT
63
#define AP_COMPASS_OFFSETS_MAX_DEFAULT 1800
64
#endif
65
66
#ifndef HAL_COMPASS_FILTER_DEFAULT
67
#define HAL_COMPASS_FILTER_DEFAULT 0 // turned off by default
68
#endif
69
70
#ifndef HAL_COMPASS_AUTO_ROT_DEFAULT
71
#define HAL_COMPASS_AUTO_ROT_DEFAULT 2
72
#endif
73
74
const AP_Param::GroupInfo Compass::var_info[] = {
75
// index 0 was used for the old orientation matrix
76
77
#ifndef HAL_BUILD_AP_PERIPH
78
// @Param: OFS_X
79
// @DisplayName: Compass offsets in milligauss on the X axis
80
// @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame
81
// @Range: -400 400
82
// @Units: mGauss
83
// @Increment: 1
84
// @User: Advanced
85
// @Calibration: 1
86
87
// @Param: OFS_Y
88
// @DisplayName: Compass offsets in milligauss on the Y axis
89
// @Description: Offset to be added to the compass y-axis values to compensate for metal in the frame
90
// @Range: -400 400
91
// @Units: mGauss
92
// @Increment: 1
93
// @User: Advanced
94
// @Calibration: 1
95
96
// @Param: OFS_Z
97
// @DisplayName: Compass offsets in milligauss on the Z axis
98
// @Description: Offset to be added to the compass z-axis values to compensate for metal in the frame
99
// @Range: -400 400
100
// @Units: mGauss
101
// @Increment: 1
102
// @User: Advanced
103
// @Calibration: 1
104
AP_GROUPINFO("OFS", 1, Compass, _state._priv_instance[0].offset, 0),
105
106
// @Param: DEC
107
// @DisplayName: Compass declination
108
// @Description: An angle to compensate between the true north and magnetic north
109
// @Range: -3.142 3.142
110
// @Units: rad
111
// @Increment: 0.01
112
// @User: Standard
113
AP_GROUPINFO("DEC", 2, Compass, _declination, 0),
114
#endif // HAL_BUILD_AP_PERIPH
115
116
#if COMPASS_LEARN_ENABLED
117
// @Param: LEARN
118
// @DisplayName: Learn compass offsets automatically
119
// @Description: Enable or disable the automatic learning of compass offsets. You can enable learning either using a compass-only method that is suitable only for fixed wing aircraft or using the offsets learnt by the active EKF state estimator. If this option is enabled then the learnt offsets are saved when you disarm the vehicle. If InFlight learning is enabled then the compass with automatically start learning once a flight starts (must be armed). While InFlight learning is running you cannot use position control modes.
120
// @Values: 0:Disabled,1:Internal-Learning,2:EKF-Learning,3:InFlight-Learning
121
// @User: Advanced
122
AP_GROUPINFO("LEARN", 3, Compass, _learn, COMPASS_LEARN_DEFAULT),
123
#endif
124
125
#ifndef HAL_BUILD_AP_PERIPH
126
// @Param: USE
127
// @DisplayName: Use compass for yaw
128
// @Description: Enable or disable the use of the compass (instead of the GPS) for determining heading
129
// @Values: 0:Disabled,1:Enabled
130
// @User: Advanced
131
AP_GROUPINFO("USE", 4, Compass, _use_for_yaw._priv_instance[0], 1), // true if used for DCM yaw
132
133
// @Param: AUTODEC
134
// @DisplayName: Auto Declination
135
// @Description: Enable or disable the automatic calculation of the declination based on gps location
136
// @Values: 0:Disabled,1:Enabled
137
// @User: Advanced
138
AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination, 1),
139
#endif
140
141
#if COMPASS_MOT_ENABLED
142
// @Param: MOTCT
143
// @DisplayName: Motor interference compensation type
144
// @Description: Set motor interference compensation type to disabled, throttle or current. Do not change manually.
145
// @Values: 0:Disabled,1:Use Throttle,2:Use Current
146
// @User: Advanced
147
// @Calibration: 1
148
AP_GROUPINFO("MOTCT", 6, Compass, _motor_comp_type, AP_COMPASS_MOT_COMP_DISABLED),
149
150
// @Param: MOT_X
151
// @DisplayName: Motor interference compensation for body frame X axis
152
// @Description: Multiplied by the current throttle and added to the compass's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
153
// @Range: -1000 1000
154
// @Units: mGauss/A
155
// @Increment: 1
156
// @User: Advanced
157
// @Calibration: 1
158
159
// @Param: MOT_Y
160
// @DisplayName: Motor interference compensation for body frame Y axis
161
// @Description: Multiplied by the current throttle and added to the compass's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
162
// @Range: -1000 1000
163
// @Units: mGauss/A
164
// @Increment: 1
165
// @User: Advanced
166
// @Calibration: 1
167
168
// @Param: MOT_Z
169
// @DisplayName: Motor interference compensation for body frame Z axis
170
// @Description: Multiplied by the current throttle and added to the compass's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
171
// @Range: -1000 1000
172
// @Units: mGauss/A
173
// @Increment: 1
174
// @User: Advanced
175
// @Calibration: 1
176
AP_GROUPINFO("MOT", 7, Compass, _state._priv_instance[0].motor_compensation, 0),
177
#endif
178
179
#ifndef HAL_BUILD_AP_PERIPH
180
// @Param: ORIENT
181
// @DisplayName: Compass orientation
182
// @Description: The orientation of the first external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles.
183
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2
184
// @User: Advanced
185
AP_GROUPINFO("ORIENT", 8, Compass, _state._priv_instance[0].orientation, ROTATION_NONE),
186
187
// @Param: EXTERNAL
188
// @DisplayName: Compass is attached via an external cable
189
// @Description: Configure compass so it is attached externally. This is auto-detected on most boards. Set to 1 if the compass is externally connected. When externally connected the COMPASS_ORIENT option operates independently of the AHRS_ORIENTATION board orientation option. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
190
// @Values: 0:Internal,1:External,2:ForcedExternal
191
// @User: Advanced
192
AP_GROUPINFO("EXTERNAL", 9, Compass, _state._priv_instance[0].external, 0),
193
#endif
194
195
#if COMPASS_MAX_INSTANCES > 1
196
// @Param: OFS2_X
197
// @DisplayName: Compass2 offsets in milligauss on the X axis
198
// @Description: Offset to be added to compass2's x-axis values to compensate for metal in the frame
199
// @Range: -400 400
200
// @Units: mGauss
201
// @Increment: 1
202
// @User: Advanced
203
// @Calibration: 1
204
205
// @Param: OFS2_Y
206
// @DisplayName: Compass2 offsets in milligauss on the Y axis
207
// @Description: Offset to be added to compass2's y-axis values to compensate for metal in the frame
208
// @Range: -400 400
209
// @Units: mGauss
210
// @Increment: 1
211
// @User: Advanced
212
// @Calibration: 1
213
214
// @Param: OFS2_Z
215
// @DisplayName: Compass2 offsets in milligauss on the Z axis
216
// @Description: Offset to be added to compass2's z-axis values to compensate for metal in the frame
217
// @Range: -400 400
218
// @Units: mGauss
219
// @Increment: 1
220
// @User: Advanced
221
// @Calibration: 1
222
AP_GROUPINFO("OFS2", 10, Compass, _state._priv_instance[1].offset, 0),
223
224
// @Param: MOT2_X
225
// @DisplayName: Motor interference compensation to compass2 for body frame X axis
226
// @Description: Multiplied by the current throttle and added to compass2's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
227
// @Range: -1000 1000
228
// @Units: mGauss/A
229
// @Increment: 1
230
// @User: Advanced
231
// @Calibration: 1
232
233
// @Param: MOT2_Y
234
// @DisplayName: Motor interference compensation to compass2 for body frame Y axis
235
// @Description: Multiplied by the current throttle and added to compass2's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
236
// @Range: -1000 1000
237
// @Units: mGauss/A
238
// @Increment: 1
239
// @User: Advanced
240
// @Calibration: 1
241
242
// @Param: MOT2_Z
243
// @DisplayName: Motor interference compensation to compass2 for body frame Z axis
244
// @Description: Multiplied by the current throttle and added to compass2's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
245
// @Range: -1000 1000
246
// @Units: mGauss/A
247
// @Increment: 1
248
// @User: Advanced
249
// @Calibration: 1
250
AP_GROUPINFO("MOT2", 11, Compass, _state._priv_instance[1].motor_compensation, 0),
251
252
#endif // COMPASS_MAX_INSTANCES
253
254
#if COMPASS_MAX_INSTANCES > 2
255
// @Param: OFS3_X
256
// @DisplayName: Compass3 offsets in milligauss on the X axis
257
// @Description: Offset to be added to compass3's x-axis values to compensate for metal in the frame
258
// @Range: -400 400
259
// @Units: mGauss
260
// @Increment: 1
261
// @User: Advanced
262
// @Calibration: 1
263
264
// @Param: OFS3_Y
265
// @DisplayName: Compass3 offsets in milligauss on the Y axis
266
// @Description: Offset to be added to compass3's y-axis values to compensate for metal in the frame
267
// @Range: -400 400
268
// @Units: mGauss
269
// @Increment: 1
270
// @User: Advanced
271
// @Calibration: 1
272
273
// @Param: OFS3_Z
274
// @DisplayName: Compass3 offsets in milligauss on the Z axis
275
// @Description: Offset to be added to compass3's z-axis values to compensate for metal in the frame
276
// @Range: -400 400
277
// @Units: mGauss
278
// @Increment: 1
279
// @User: Advanced
280
// @Calibration: 1
281
AP_GROUPINFO("OFS3", 13, Compass, _state._priv_instance[2].offset, 0),
282
283
// @Param: MOT3_X
284
// @DisplayName: Motor interference compensation to compass3 for body frame X axis
285
// @Description: Multiplied by the current throttle and added to compass3's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
286
// @Range: -1000 1000
287
// @Units: mGauss/A
288
// @Increment: 1
289
// @User: Advanced
290
// @Calibration: 1
291
292
// @Param: MOT3_Y
293
// @DisplayName: Motor interference compensation to compass3 for body frame Y axis
294
// @Description: Multiplied by the current throttle and added to compass3's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
295
// @Range: -1000 1000
296
// @Units: mGauss/A
297
// @Increment: 1
298
// @User: Advanced
299
// @Calibration: 1
300
301
// @Param: MOT3_Z
302
// @DisplayName: Motor interference compensation to compass3 for body frame Z axis
303
// @Description: Multiplied by the current throttle and added to compass3's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
304
// @Range: -1000 1000
305
// @Units: mGauss/A
306
// @Increment: 1
307
// @User: Advanced
308
// @Calibration: 1
309
AP_GROUPINFO("MOT3", 14, Compass, _state._priv_instance[2].motor_compensation, 0),
310
#endif // COMPASS_MAX_INSTANCES
311
312
// @Param: DEV_ID
313
// @DisplayName: Compass device id
314
// @Description: Compass device id. Automatically detected, do not set manually
315
// @ReadOnly: True
316
// @User: Advanced
317
AP_GROUPINFO("DEV_ID", 15, Compass, _state._priv_instance[0].dev_id, 0),
318
319
#if COMPASS_MAX_INSTANCES > 1
320
// @Param: DEV_ID2
321
// @DisplayName: Compass2 device id
322
// @Description: Second compass's device id. Automatically detected, do not set manually
323
// @ReadOnly: True
324
// @User: Advanced
325
AP_GROUPINFO("DEV_ID2", 16, Compass, _state._priv_instance[1].dev_id, 0),
326
#endif // COMPASS_MAX_INSTANCES
327
328
#if COMPASS_MAX_INSTANCES > 2
329
// @Param: DEV_ID3
330
// @DisplayName: Compass3 device id
331
// @Description: Third compass's device id. Automatically detected, do not set manually
332
// @ReadOnly: True
333
// @User: Advanced
334
AP_GROUPINFO("DEV_ID3", 17, Compass, _state._priv_instance[2].dev_id, 0),
335
#endif // COMPASS_MAX_INSTANCES
336
337
#if COMPASS_MAX_INSTANCES > 1
338
// @Param: USE2
339
// @DisplayName: Compass2 used for yaw
340
// @Description: Enable or disable the secondary compass for determining heading.
341
// @Values: 0:Disabled,1:Enabled
342
// @User: Advanced
343
AP_GROUPINFO("USE2", 18, Compass, _use_for_yaw._priv_instance[1], 1),
344
345
// @Param: ORIENT2
346
// @DisplayName: Compass2 orientation
347
// @Description: The orientation of a second external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles.
348
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2
349
// @User: Advanced
350
AP_GROUPINFO("ORIENT2", 19, Compass, _state._priv_instance[1].orientation, ROTATION_NONE),
351
352
// @Param: EXTERN2
353
// @DisplayName: Compass2 is attached via an external cable
354
// @Description: Configure second compass so it is attached externally. This is auto-detected on most boards. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
355
// @Values: 0:Internal,1:External,2:ForcedExternal
356
// @User: Advanced
357
AP_GROUPINFO("EXTERN2",20, Compass, _state._priv_instance[1].external, 0),
358
#endif // COMPASS_MAX_INSTANCES
359
360
#if COMPASS_MAX_INSTANCES > 2
361
// @Param: USE3
362
// @DisplayName: Compass3 used for yaw
363
// @Description: Enable or disable the tertiary compass for determining heading.
364
// @Values: 0:Disabled,1:Enabled
365
// @User: Advanced
366
AP_GROUPINFO("USE3", 21, Compass, _use_for_yaw._priv_instance[2], 1),
367
368
// @Param: ORIENT3
369
// @DisplayName: Compass3 orientation
370
// @Description: The orientation of a third external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles.
371
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2
372
// @User: Advanced
373
AP_GROUPINFO("ORIENT3", 22, Compass, _state._priv_instance[2].orientation, ROTATION_NONE),
374
375
// @Param: EXTERN3
376
// @DisplayName: Compass3 is attached via an external cable
377
// @Description: Configure third compass so it is attached externally. This is auto-detected on most boards. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
378
// @Values: 0:Internal,1:External,2:ForcedExternal
379
// @User: Advanced
380
AP_GROUPINFO("EXTERN3",23, Compass, _state._priv_instance[2].external, 0),
381
#endif // COMPASS_MAX_INSTANCES
382
383
#if AP_COMPASS_DIAGONALS_ENABLED
384
// @Param: DIA_X
385
// @DisplayName: Compass soft-iron diagonal X component
386
// @Description: DIA_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
387
// @User: Advanced
388
// @Calibration: 1
389
390
// @Param: DIA_Y
391
// @DisplayName: Compass soft-iron diagonal Y component
392
// @Description: DIA_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
393
// @User: Advanced
394
// @Calibration: 1
395
396
// @Param: DIA_Z
397
// @DisplayName: Compass soft-iron diagonal Z component
398
// @Description: DIA_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
399
// @User: Advanced
400
// @Calibration: 1
401
AP_GROUPINFO("DIA", 24, Compass, _state._priv_instance[0].diagonals, 1.0),
402
403
// @Param: ODI_X
404
// @DisplayName: Compass soft-iron off-diagonal X component
405
// @Description: ODI_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
406
// @User: Advanced
407
// @Calibration: 1
408
409
// @Param: ODI_Y
410
// @DisplayName: Compass soft-iron off-diagonal Y component
411
// @Description: ODI_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
412
// @User: Advanced
413
// @Calibration: 1
414
415
// @Param: ODI_Z
416
// @DisplayName: Compass soft-iron off-diagonal Z component
417
// @Description: ODI_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
418
// @User: Advanced
419
// @Calibration: 1
420
AP_GROUPINFO("ODI", 25, Compass, _state._priv_instance[0].offdiagonals, 0),
421
422
#if COMPASS_MAX_INSTANCES > 1
423
// @Param: DIA2_X
424
// @DisplayName: Compass2 soft-iron diagonal X component
425
// @Description: DIA_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
426
// @User: Advanced
427
// @Calibration: 1
428
429
// @Param: DIA2_Y
430
// @DisplayName: Compass2 soft-iron diagonal Y component
431
// @Description: DIA_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
432
// @User: Advanced
433
// @Calibration: 1
434
435
// @Param: DIA2_Z
436
// @DisplayName: Compass2 soft-iron diagonal Z component
437
// @Description: DIA_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
438
// @User: Advanced
439
// @Calibration: 1
440
AP_GROUPINFO("DIA2", 26, Compass, _state._priv_instance[1].diagonals, 1.0),
441
442
// @Param: ODI2_X
443
// @DisplayName: Compass2 soft-iron off-diagonal X component
444
// @Description: ODI_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
445
// @User: Advanced
446
// @Calibration: 1
447
448
// @Param: ODI2_Y
449
// @DisplayName: Compass2 soft-iron off-diagonal Y component
450
// @Description: ODI_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
451
// @User: Advanced
452
// @Calibration: 1
453
454
// @Param: ODI2_Z
455
// @DisplayName: Compass2 soft-iron off-diagonal Z component
456
// @Description: ODI_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
457
// @User: Advanced
458
// @Calibration: 1
459
AP_GROUPINFO("ODI2", 27, Compass, _state._priv_instance[1].offdiagonals, 0),
460
#endif // COMPASS_MAX_INSTANCES
461
462
#if COMPASS_MAX_INSTANCES > 2
463
// @Param: DIA3_X
464
// @DisplayName: Compass3 soft-iron diagonal X component
465
// @Description: DIA_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
466
// @User: Advanced
467
// @Calibration: 1
468
469
// @Param: DIA3_Y
470
// @DisplayName: Compass3 soft-iron diagonal Y component
471
// @Description: DIA_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
472
// @User: Advanced
473
// @Calibration: 1
474
475
// @Param: DIA3_Z
476
// @DisplayName: Compass3 soft-iron diagonal Z component
477
// @Description: DIA_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
478
// @User: Advanced
479
// @Calibration: 1
480
AP_GROUPINFO("DIA3", 28, Compass, _state._priv_instance[2].diagonals, 1.0),
481
482
// @Param: ODI3_X
483
// @DisplayName: Compass3 soft-iron off-diagonal X component
484
// @Description: ODI_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
485
// @User: Advanced
486
// @Calibration: 1
487
488
// @Param: ODI3_Y
489
// @DisplayName: Compass3 soft-iron off-diagonal Y component
490
// @Description: ODI_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
491
// @User: Advanced
492
// @Calibration: 1
493
494
// @Param: ODI3_Z
495
// @DisplayName: Compass3 soft-iron off-diagonal Z component
496
// @Description: ODI_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
497
// @User: Advanced
498
// @Calibration: 1
499
AP_GROUPINFO("ODI3", 29, Compass, _state._priv_instance[2].offdiagonals, 0),
500
#endif // COMPASS_MAX_INSTANCES
501
#endif // AP_COMPASS_DIAGONALS_ENABLED
502
503
#if COMPASS_CAL_ENABLED
504
// @Param: CAL_FIT
505
// @DisplayName: Compass calibration fitness
506
// @Description: This controls the fitness level required for a successful compass calibration. A lower value makes for a stricter fit (less likely to pass). This is the value used for the primary magnetometer. Other magnetometers get double the value.
507
// @Range: 4 32
508
// @Values: 4:Very Strict,8:Strict,16:Default,32:Relaxed
509
// @Increment: 0.1
510
// @User: Advanced
511
AP_GROUPINFO("CAL_FIT", 30, Compass, _calibration_threshold, AP_COMPASS_CALIBRATION_FITNESS_DEFAULT),
512
#endif
513
514
#ifndef HAL_BUILD_AP_PERIPH
515
// @Param: OFFS_MAX
516
// @DisplayName: Compass maximum offset
517
// @Description: This sets the maximum allowed compass offset in calibration and arming checks
518
// @Range: 500 3000
519
// @Increment: 1
520
// @User: Advanced
521
AP_GROUPINFO("OFFS_MAX", 31, Compass, _offset_max, AP_COMPASS_OFFSETS_MAX_DEFAULT),
522
#endif
523
524
#if COMPASS_MOT_ENABLED
525
// @Group: PMOT
526
// @Path: Compass_PerMotor.cpp
527
AP_SUBGROUPINFO(_per_motor, "PMOT", 32, Compass, Compass_PerMotor),
528
#endif
529
530
// @Param: DISBLMSK
531
// @DisplayName: Compass disable driver type mask
532
// @Description: This is a bitmask of driver types to disable. If a driver type is set in this mask then that driver will not try to find a sensor at startup
533
// @Bitmask: 0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,11:DroneCAN,12:QMC5883,14:MAG3110,15:IST8308,16:RM3100,17:MSP,18:ExternalAHRS,19:MMC5XX3,20:QMC5883P,21:BMM350,22:IIS2MDC
534
// @User: Advanced
535
AP_GROUPINFO("DISBLMSK", 33, Compass, _driver_type_mask, 0),
536
537
// @Param: FLTR_RNG
538
// @DisplayName: Range in which sample is accepted
539
// @Description: This sets the range around the average value that new samples must be within to be accepted. This can help reduce the impact of noise on sensors that are on long I2C cables. The value is a percentage from the average value. A value of zero disables this filter.
540
// @Units: %
541
// @Range: 0 100
542
// @Increment: 1
543
AP_GROUPINFO("FLTR_RNG", 34, Compass, _filter_range, HAL_COMPASS_FILTER_DEFAULT),
544
545
#if COMPASS_CAL_ENABLED
546
// @Param: AUTO_ROT
547
// @DisplayName: Automatically check orientation
548
// @Description: When enabled this will automatically check the orientation of compasses on successful completion of compass calibration. If set to 2 then external compasses will have their orientation automatically corrected.
549
// @Values: 0:Disabled,1:CheckOnly,2:CheckAndFix,3:use same tolerance to auto rotate 45 deg rotations
550
AP_GROUPINFO("AUTO_ROT", 35, Compass, _rotate_auto, HAL_COMPASS_AUTO_ROT_DEFAULT),
551
#endif
552
553
#if COMPASS_MAX_INSTANCES > 1
554
// @Param: PRIO1_ID
555
// @DisplayName: Compass device id with 1st order priority
556
// @Description: Compass device id with 1st order priority, set automatically if 0. Reboot required after change.
557
// @RebootRequired: True
558
// @User: Advanced
559
AP_GROUPINFO("PRIO1_ID", 36, Compass, _priority_did_stored_list._priv_instance[0], 0),
560
561
// @Param: PRIO2_ID
562
// @DisplayName: Compass device id with 2nd order priority
563
// @Description: Compass device id with 2nd order priority, set automatically if 0. Reboot required after change.
564
// @RebootRequired: True
565
// @User: Advanced
566
AP_GROUPINFO("PRIO2_ID", 37, Compass, _priority_did_stored_list._priv_instance[1], 0),
567
#endif // COMPASS_MAX_INSTANCES
568
569
#if COMPASS_MAX_INSTANCES > 2
570
// @Param: PRIO3_ID
571
// @DisplayName: Compass device id with 3rd order priority
572
// @Description: Compass device id with 3rd order priority, set automatically if 0. Reboot required after change.
573
// @RebootRequired: True
574
// @User: Advanced
575
AP_GROUPINFO("PRIO3_ID", 38, Compass, _priority_did_stored_list._priv_instance[2], 0),
576
#endif // COMPASS_MAX_INSTANCES
577
578
// @Param: ENABLE
579
// @DisplayName: Enable Compass
580
// @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass. Note that this is separate from COMPASS_USE. This will enable the low level senor, and will enable logging of magnetometer data. To use the compass for navigation you must also set COMPASS_USE to 1.
581
// @User: Standard
582
// @RebootRequired: True
583
// @Values: 0:Disabled,1:Enabled
584
AP_GROUPINFO("ENABLE", 39, Compass, _enabled, AP_COMPASS_ENABLE_DEFAULT),
585
586
#ifndef HAL_BUILD_AP_PERIPH
587
// @Param: SCALE
588
// @DisplayName: Compass1 scale factor
589
// @Description: Scaling factor for first compass to compensate for sensor scaling errors. If this is 0 then no scaling is done
590
// @User: Standard
591
// @Range: 0 1.3
592
AP_GROUPINFO("SCALE", 40, Compass, _state._priv_instance[0].scale_factor, 0),
593
594
#if COMPASS_MAX_INSTANCES > 1
595
// @Param: SCALE2
596
// @DisplayName: Compass2 scale factor
597
// @Description: Scaling factor for 2nd compass to compensate for sensor scaling errors. If this is 0 then no scaling is done
598
// @User: Standard
599
// @Range: 0 1.3
600
AP_GROUPINFO("SCALE2", 41, Compass, _state._priv_instance[1].scale_factor, 0),
601
#endif
602
603
#if COMPASS_MAX_INSTANCES > 2
604
// @Param: SCALE3
605
// @DisplayName: Compass3 scale factor
606
// @Description: Scaling factor for 3rd compass to compensate for sensor scaling errors. If this is 0 then no scaling is done
607
// @User: Standard
608
// @Range: 0 1.3
609
AP_GROUPINFO("SCALE3", 42, Compass, _state._priv_instance[2].scale_factor, 0),
610
#endif
611
#endif // HAL_BUILD_AP_PERIPH
612
613
#ifndef HAL_BUILD_AP_PERIPH
614
// @Param: OPTIONS
615
// @DisplayName: Compass options
616
// @Description: This sets options to change the behaviour of the compass
617
// @Bitmask: 0:CalRequireGPS
618
// @Bitmask: 1: Allow missing DroneCAN compasses to be automaticaly replaced (calibration still required)
619
// @User: Advanced
620
AP_GROUPINFO("OPTIONS", 43, Compass, _options, 0),
621
#endif
622
623
#if COMPASS_MAX_UNREG_DEV > 0
624
// @Param: DEV_ID4
625
// @DisplayName: Compass4 device id
626
// @Description: Extra 4th compass's device id. Automatically detected, do not set manually
627
// @ReadOnly: True
628
// @User: Advanced
629
AP_GROUPINFO("DEV_ID4", 44, Compass, extra_dev_id[0], 0),
630
#endif // COMPASS_MAX_UNREG_DEV
631
632
#if COMPASS_MAX_UNREG_DEV > 1
633
// @Param: DEV_ID5
634
// @DisplayName: Compass5 device id
635
// @Description: Extra 5th compass's device id. Automatically detected, do not set manually
636
// @ReadOnly: True
637
// @User: Advanced
638
AP_GROUPINFO("DEV_ID5", 45, Compass, extra_dev_id[1], 0),
639
#endif // COMPASS_MAX_UNREG_DEV
640
641
#if COMPASS_MAX_UNREG_DEV > 2
642
// @Param: DEV_ID6
643
// @DisplayName: Compass6 device id
644
// @Description: Extra 6th compass's device id. Automatically detected, do not set manually
645
// @ReadOnly: True
646
// @User: Advanced
647
AP_GROUPINFO("DEV_ID6", 46, Compass, extra_dev_id[2], 0),
648
#endif // COMPASS_MAX_UNREG_DEV
649
650
#if COMPASS_MAX_UNREG_DEV > 3
651
// @Param: DEV_ID7
652
// @DisplayName: Compass7 device id
653
// @Description: Extra 7th compass's device id. Automatically detected, do not set manually
654
// @ReadOnly: True
655
// @User: Advanced
656
AP_GROUPINFO("DEV_ID7", 47, Compass, extra_dev_id[3], 0),
657
#endif // COMPASS_MAX_UNREG_DEV
658
659
#if COMPASS_MAX_UNREG_DEV > 4
660
// @Param: DEV_ID8
661
// @DisplayName: Compass8 device id
662
// @Description: Extra 8th compass's device id. Automatically detected, do not set manually
663
// @ReadOnly: True
664
// @User: Advanced
665
AP_GROUPINFO("DEV_ID8", 48, Compass, extra_dev_id[4], 0),
666
#endif // COMPASS_MAX_UNREG_DEV
667
668
// @Param: CUS_ROLL
669
// @DisplayName: Custom orientation roll offset
670
// @Description: Compass mounting position roll offset. Positive values = roll right, negative values = roll left. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.
671
// @Range: -180 180
672
// @Units: deg
673
// @Increment: 1
674
// @RebootRequired: True
675
// @User: Advanced
676
677
// index 49
678
679
// @Param: CUS_PIT
680
// @DisplayName: Custom orientation pitch offset
681
// @Description: Compass mounting position pitch offset. Positive values = pitch up, negative values = pitch down. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.
682
// @Range: -180 180
683
// @Units: deg
684
// @Increment: 1
685
// @RebootRequired: True
686
// @User: Advanced
687
688
// index 50
689
690
// @Param: CUS_YAW
691
// @DisplayName: Custom orientation yaw offset
692
// @Description: Compass mounting position yaw offset. Positive values = yaw right, negative values = yaw left. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.
693
// @Range: -180 180
694
// @Units: deg
695
// @Increment: 1
696
// @RebootRequired: True
697
// @User: Advanced
698
699
// index 51
700
701
AP_GROUPEND
702
};
703
704
// Default constructor.
705
// Note that the Vector/Matrix constructors already implicitly zero
706
// their values.
707
//
708
Compass::Compass(void)
709
{
710
if (_singleton != nullptr) {
711
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
712
AP_HAL::panic("Compass must be singleton");
713
#endif
714
return;
715
}
716
_singleton = this;
717
AP_Param::setup_object_defaults(this, var_info);
718
}
719
720
// Default init method
721
//
722
void Compass::init()
723
{
724
if (!_enabled) {
725
return;
726
}
727
728
/*
729
on init() if any devid is set then we set suppress_devid_save to
730
false. This is used to determine if we save device ids during
731
the init process.
732
*/
733
suppress_devid_save = true;
734
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
735
if (_state._priv_instance[i].dev_id != 0) {
736
suppress_devid_save = false;
737
break;
738
}
739
#if COMPASS_MAX_INSTANCES > 1
740
if (_priority_did_stored_list._priv_instance[i] != 0) {
741
suppress_devid_save = false;
742
break;
743
}
744
#endif
745
}
746
747
// convert to new custom rotation method
748
// PARAMETER_CONVERSION - Added: Nov-2021
749
#if AP_CUSTOMROTATIONS_ENABLED
750
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
751
if (_state[i].orientation != ROTATION_CUSTOM_OLD) {
752
continue;
753
}
754
_state[i].orientation.set_and_save(ROTATION_CUSTOM_2);
755
AP_Param::ConversionInfo info;
756
if (AP_Param::find_top_level_key_by_pointer(this, info.old_key)) {
757
info.type = AP_PARAM_FLOAT;
758
float rpy[3] = {};
759
AP_Float rpy_param;
760
for (info.old_group_element=49; info.old_group_element<=51; info.old_group_element++) {
761
if (AP_Param::find_old_parameter(&info, &rpy_param)) {
762
rpy[info.old_group_element-49] = rpy_param.get();
763
}
764
}
765
AP::custom_rotations().convert(ROTATION_CUSTOM_2, rpy[0], rpy[1], rpy[2]);
766
}
767
break;
768
}
769
#endif // AP_CUSTOMROTATIONS_ENABLED
770
771
#if COMPASS_MAX_INSTANCES > 1
772
// Look if there was a primary compass setup in previous version
773
// if so and the primary compass is not set in current setup
774
// make the devid as primary.
775
if (_priority_did_stored_list[Priority(0)] == 0) {
776
uint16_t k_param_compass;
777
if (AP_Param::find_top_level_key_by_pointer(this, k_param_compass)) {
778
const AP_Param::ConversionInfo primary_compass_old_param = {k_param_compass, 12, AP_PARAM_INT8, ""};
779
AP_Int8 value;
780
value.set(0);
781
bool primary_param_exists = AP_Param::find_old_parameter(&primary_compass_old_param, &value);
782
int8_t oldvalue = value.get();
783
if ((oldvalue!=0) && (oldvalue<COMPASS_MAX_INSTANCES) && primary_param_exists) {
784
_priority_did_stored_list[Priority(0)].set_and_save_ifchanged(_state[StateIndex(oldvalue)].dev_id);
785
}
786
}
787
}
788
789
// Load priority list from storage, the changes to priority list
790
// by user only take effect post reboot, after this
791
if (!suppress_devid_save) {
792
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
793
if (_priority_did_stored_list[i] != 0) {
794
_priority_did_list[i] = _priority_did_stored_list[i];
795
} else {
796
// Maintain a list without gaps and duplicates
797
for (Priority j(i+1); j<COMPASS_MAX_INSTANCES; j++) {
798
int32_t temp;
799
if (_priority_did_stored_list[j] == _priority_did_stored_list[i]) {
800
_priority_did_stored_list[j].set_and_save_ifchanged(0);
801
}
802
if (_priority_did_stored_list[j] == 0) {
803
continue;
804
}
805
temp = _priority_did_stored_list[j];
806
_priority_did_stored_list[j].set_and_save_ifchanged(0);
807
_priority_did_list[i] = temp;
808
_priority_did_stored_list[i].set_and_save_ifchanged(temp);
809
break;
810
}
811
}
812
}
813
}
814
#endif // COMPASS_MAX_INSTANCES
815
816
// cache expected dev ids for use during runtime detection
817
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
818
_state[i].expected_dev_id = _state[i].dev_id;
819
}
820
821
#if COMPASS_MAX_UNREG_DEV
822
// set the dev_id to 0 for undetected compasses. extra_dev_id is just an
823
// interface for users to see unreg compasses, we actually never store it
824
// in storage.
825
for (uint8_t i=_unreg_compass_count; i<COMPASS_MAX_UNREG_DEV; i++) {
826
// cache the extra devices detected in last boot
827
// for detecting replacement mag
828
_previously_unreg_mag[i] = extra_dev_id[i];
829
extra_dev_id[i].set(0);
830
}
831
#endif
832
833
#if COMPASS_MAX_INSTANCES > 1
834
// This method calls set_and_save_ifchanged on parameters
835
// which are set() but not saved() during normal runtime,
836
// do not move this call without ensuring that is not happening
837
// read comments under set_and_save_ifchanged for details
838
if (!suppress_devid_save) {
839
_reorder_compass_params();
840
}
841
#endif
842
843
if (_compass_count == 0) {
844
// detect available backends. Only called once
845
_detect_backends();
846
}
847
848
if (_compass_count != 0) {
849
// get initial health status
850
hal.scheduler->delay(100);
851
read();
852
}
853
// set the dev_id to 0 for undetected compasses, to make it easier
854
// for users to see how many compasses are detected. We don't do a
855
// set_and_save() as the user may have temporarily removed the
856
// compass, and we don't want to force a re-cal if they plug it
857
// back in again
858
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
859
if (!_state[i].registered) {
860
_state[i].dev_id.set(0);
861
}
862
}
863
864
#ifndef HAL_BUILD_AP_PERIPH
865
// updating the AHRS orientation updates our own orientation:
866
AP::ahrs().update_orientation();
867
#endif
868
869
init_done = true;
870
suppress_devid_save = false;
871
}
872
873
#if COMPASS_MAX_INSTANCES > 1 || COMPASS_MAX_UNREG_DEV
874
// Update Priority List for Mags, by default, we just
875
// load them as they come up the first time
876
Compass::Priority Compass::_update_priority_list(int32_t dev_id)
877
{
878
// Check if already in priority list
879
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
880
if (_priority_did_list[i] == dev_id) {
881
if (i >= _compass_count) {
882
_compass_count = uint8_t(i)+1;
883
}
884
return i;
885
}
886
}
887
888
// We are not in priority list, let's add at first empty
889
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
890
if (_priority_did_stored_list[i] == 0) {
891
if (suppress_devid_save) {
892
_priority_did_stored_list[i].set(dev_id);
893
} else {
894
_priority_did_stored_list[i].set_and_save(dev_id);
895
}
896
_priority_did_list[i] = dev_id;
897
if (i >= _compass_count) {
898
_compass_count = uint8_t(i)+1;
899
}
900
return i;
901
}
902
}
903
return Priority(COMPASS_MAX_INSTANCES);
904
}
905
#endif
906
907
908
#if COMPASS_MAX_INSTANCES > 1
909
// This method reorganises devid list to match
910
// priority list, only call before detection at boot
911
void Compass::_reorder_compass_params()
912
{
913
mag_state swap_state;
914
StateIndex curr_state_id;
915
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
916
if (_priority_did_list[i] == 0) {
917
continue;
918
}
919
curr_state_id = COMPASS_MAX_INSTANCES;
920
for (StateIndex j(0); j<COMPASS_MAX_INSTANCES; j++) {
921
if (_priority_did_list[i] == _state[j].dev_id) {
922
curr_state_id = j;
923
break;
924
}
925
}
926
if (curr_state_id != COMPASS_MAX_INSTANCES && uint8_t(curr_state_id) != uint8_t(i)) {
927
//let's swap
928
swap_state.copy_from(_state[curr_state_id]);
929
_state[curr_state_id].copy_from(_state[StateIndex(uint8_t(i))]);
930
_state[StateIndex(uint8_t(i))].copy_from(swap_state);
931
}
932
}
933
}
934
#endif
935
936
void Compass::mag_state::copy_from(const Compass::mag_state& state)
937
{
938
external.set_and_save_ifchanged(state.external);
939
orientation.set_and_save_ifchanged(state.orientation);
940
offset.set_and_save_ifchanged(state.offset);
941
#if AP_COMPASS_DIAGONALS_ENABLED
942
diagonals.set_and_save_ifchanged(state.diagonals);
943
offdiagonals.set_and_save_ifchanged(state.offdiagonals);
944
#endif
945
scale_factor.set_and_save_ifchanged(state.scale_factor);
946
dev_id.set_and_save_ifchanged(state.dev_id);
947
motor_compensation.set_and_save_ifchanged(state.motor_compensation);
948
expected_dev_id = state.expected_dev_id;
949
detected_dev_id = state.detected_dev_id;
950
}
951
// Register a new compass instance
952
//
953
bool Compass::register_compass(int32_t dev_id, uint8_t& instance)
954
{
955
956
#if COMPASS_MAX_INSTANCES == 1 && !COMPASS_MAX_UNREG_DEV
957
// simple single compass setup for AP_Periph
958
Priority priority(0);
959
StateIndex i(0);
960
if (_state[i].registered) {
961
return false;
962
}
963
_state[i].registered = true;
964
_state[i].priority = priority;
965
instance = uint8_t(i);
966
_compass_count = 1;
967
return true;
968
#else
969
Priority priority;
970
// Check if we already have this dev_id registered
971
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
972
priority = _update_priority_list(dev_id);
973
if (_state[i].expected_dev_id == dev_id && priority < COMPASS_MAX_INSTANCES) {
974
_state[i].registered = true;
975
_state[i].priority = priority;
976
instance = uint8_t(i);
977
return true;
978
}
979
}
980
981
// This is an unregistered compass, check if any free slot is available
982
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
983
priority = _update_priority_list(dev_id);
984
if (_state[i].dev_id == 0 && priority < COMPASS_MAX_INSTANCES) {
985
_state[i].registered = true;
986
_state[i].priority = priority;
987
instance = uint8_t(i);
988
return true;
989
}
990
}
991
992
// This might be a replacement compass module, find any unregistered compass
993
// instance and replace that
994
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
995
priority = _update_priority_list(dev_id);
996
if (!_state[i].registered && priority < COMPASS_MAX_INSTANCES) {
997
_state[i].registered = true;
998
_state[i].priority = priority;
999
instance = uint8_t(i);
1000
return true;
1001
}
1002
}
1003
#endif
1004
1005
#if COMPASS_MAX_UNREG_DEV
1006
// Set extra dev id
1007
if (_unreg_compass_count >= COMPASS_MAX_UNREG_DEV) {
1008
AP_HAL::panic("Too many compass instances");
1009
}
1010
1011
for (uint8_t i=0; i<COMPASS_MAX_UNREG_DEV; i++) {
1012
if (extra_dev_id[i] == dev_id) {
1013
if (i >= _unreg_compass_count) {
1014
_unreg_compass_count = i+1;
1015
}
1016
instance = i+COMPASS_MAX_INSTANCES;
1017
return false;
1018
} else if (extra_dev_id[i] == 0) {
1019
extra_dev_id[_unreg_compass_count++].set(dev_id);
1020
instance = i+COMPASS_MAX_INSTANCES;
1021
return false;
1022
}
1023
}
1024
#else
1025
AP_HAL::panic("Too many compass instances");
1026
#endif
1027
1028
return false;
1029
}
1030
1031
Compass::StateIndex Compass::_get_state_id(Compass::Priority priority) const
1032
{
1033
#if COMPASS_MAX_INSTANCES > 1
1034
if (_priority_did_list[priority] == 0) {
1035
return StateIndex(COMPASS_MAX_INSTANCES);
1036
}
1037
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
1038
if (_priority_did_list[priority] == _state[i].detected_dev_id) {
1039
return i;
1040
}
1041
}
1042
return StateIndex(COMPASS_MAX_INSTANCES);
1043
#else
1044
return StateIndex(0);
1045
#endif
1046
}
1047
1048
bool Compass::_add_backend(AP_Compass_Backend *backend)
1049
{
1050
if (!backend) {
1051
return false;
1052
}
1053
1054
if (_backend_count == COMPASS_MAX_BACKEND) {
1055
return false;
1056
}
1057
1058
_backends[_backend_count++] = backend;
1059
1060
return true;
1061
}
1062
1063
/*
1064
return true if a driver type is enabled
1065
*/
1066
bool Compass::_driver_enabled(enum DriverType driver_type)
1067
{
1068
uint32_t mask = (1U<<uint8_t(driver_type));
1069
return (mask & uint32_t(_driver_type_mask.get())) == 0;
1070
}
1071
1072
/*
1073
wrapper around hal.i2c_mgr->get_device() that prevents duplicate devices being opened
1074
*/
1075
bool Compass::_have_i2c_driver(uint8_t bus, uint8_t address) const
1076
{
1077
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
1078
if (!_state[i].registered) {
1079
continue;
1080
}
1081
if (AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C, bus, address, 0) ==
1082
AP_HAL::Device::change_bus_id(uint32_t(_state[i].dev_id.get()), 0)) {
1083
// we are already using this device
1084
return true;
1085
}
1086
}
1087
return false;
1088
}
1089
1090
#if COMPASS_MAX_UNREG_DEV > 0
1091
#define CHECK_UNREG_LIMIT_RETURN if (_unreg_compass_count == COMPASS_MAX_UNREG_DEV) return
1092
#else
1093
#define CHECK_UNREG_LIMIT_RETURN
1094
#endif
1095
1096
/*
1097
macro to add a backend with check for too many backends or compass
1098
instances. We don't try to start more than the maximum allowed
1099
*/
1100
#define ADD_BACKEND(driver_type, backend) \
1101
do { if (_driver_enabled(driver_type)) { _add_backend(backend); } \
1102
CHECK_UNREG_LIMIT_RETURN; \
1103
} while (0)
1104
1105
#define GET_I2C_DEVICE(bus, address) _have_i2c_driver(bus, address)?nullptr:hal.i2c_mgr->get_device(bus, address)
1106
1107
/*
1108
look for compasses on external i2c buses
1109
*/
1110
void Compass::_probe_external_i2c_compasses(void)
1111
{
1112
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1113
bool all_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2);
1114
(void)all_external; // in case all backends using this are compiled out
1115
#endif
1116
#if AP_COMPASS_HMC5843_ENABLED
1117
// external i2c bus
1118
FOREACH_I2C_EXTERNAL(i) {
1119
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
1120
true, ROTATION_ROLL_180));
1121
}
1122
1123
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1124
if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_MINDPXV2 &&
1125
AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_AEROFC) {
1126
// internal i2c bus
1127
FOREACH_I2C_INTERNAL(i) {
1128
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),
1129
all_external, all_external?ROTATION_ROLL_180:ROTATION_YAW_270));
1130
}
1131
}
1132
#endif // !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1133
#endif // AP_COMPASS_HMC5843_ENABLED
1134
1135
#if AP_COMPASS_QMC5883L_ENABLED
1136
//external i2c bus
1137
FOREACH_I2C_EXTERNAL(i) {
1138
ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
1139
true, HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL));
1140
}
1141
1142
// internal i2c bus
1143
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1144
if (all_external) {
1145
// only probe QMC5883L on internal if we are treating internals as externals
1146
FOREACH_I2C_INTERNAL(i) {
1147
ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),
1148
all_external,
1149
all_external?HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL));
1150
}
1151
}
1152
#endif
1153
#endif // AP_COMPASS_QMC5883L_ENABLED
1154
1155
#if AP_COMPASS_QMC5883P_ENABLED
1156
//external i2c bus
1157
FOREACH_I2C_EXTERNAL(i) {
1158
ADD_BACKEND(DRIVER_QMC5883P, AP_Compass_QMC5883P::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883P_I2C_ADDR),
1159
true, HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL));
1160
}
1161
1162
// internal i2c bus
1163
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1164
if (all_external) {
1165
// only probe QMC5883P on internal if we are treating internals as externals
1166
FOREACH_I2C_INTERNAL(i) {
1167
ADD_BACKEND(DRIVER_QMC5883P, AP_Compass_QMC5883P::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883P_I2C_ADDR),
1168
all_external,
1169
all_external?HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883P_ORIENTATION_INTERNAL));
1170
}
1171
}
1172
#endif
1173
#endif // AP_COMPASS_QMC5883P_ENABLED
1174
1175
#if AP_COMPASS_IIS2MDC_ENABLED
1176
//external i2c bus
1177
FOREACH_I2C_EXTERNAL(i) {
1178
ADD_BACKEND(DRIVER_IIS2MDC, AP_Compass_IIS2MDC::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IIS2MDC_I2C_ADDR),
1179
true, HAL_COMPASS_IIS2MDC_ORIENTATION_EXTERNAL));
1180
}
1181
1182
// internal i2c bus
1183
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1184
if (all_external) {
1185
// only probe IIS2MDC on internal if we are treating internals as externals
1186
FOREACH_I2C_INTERNAL(i) {
1187
ADD_BACKEND(DRIVER_IIS2MDC, AP_Compass_IIS2MDC::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IIS2MDC_I2C_ADDR),
1188
all_external,
1189
all_external?HAL_COMPASS_IIS2MDC_ORIENTATION_EXTERNAL:HAL_COMPASS_IIS2MDC_ORIENTATION_INTERNAL));
1190
}
1191
}
1192
#endif
1193
#endif // AP_COMPASS_QMC5883P_ENABLED
1194
1195
#ifndef HAL_BUILD_AP_PERIPH
1196
// AK09916 on ICM20948
1197
#if AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED
1198
FOREACH_I2C_EXTERNAL(i) {
1199
ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
1200
GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),
1201
true, ROTATION_PITCH_180_YAW_90));
1202
ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
1203
GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR2),
1204
true, ROTATION_PITCH_180_YAW_90));
1205
}
1206
1207
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1208
FOREACH_I2C_INTERNAL(i) {
1209
ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
1210
GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),
1211
all_external, ROTATION_PITCH_180_YAW_90));
1212
ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
1213
GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR2),
1214
all_external, ROTATION_PITCH_180_YAW_90));
1215
}
1216
#endif
1217
#endif // AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED
1218
#endif // HAL_BUILD_AP_PERIPH
1219
1220
#if AP_COMPASS_LIS3MDL_ENABLED
1221
// lis3mdl on bus 0 with default address
1222
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1223
FOREACH_I2C_INTERNAL(i) {
1224
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
1225
all_external, all_external?ROTATION_YAW_90:ROTATION_NONE));
1226
}
1227
1228
// lis3mdl on bus 0 with alternate address
1229
FOREACH_I2C_INTERNAL(i) {
1230
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
1231
all_external, all_external?ROTATION_YAW_90:ROTATION_NONE));
1232
}
1233
#endif
1234
// external lis3mdl on bus 1 with default address
1235
FOREACH_I2C_EXTERNAL(i) {
1236
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),
1237
true, ROTATION_YAW_90));
1238
}
1239
1240
// external lis3mdl on bus 1 with alternate address
1241
FOREACH_I2C_EXTERNAL(i) {
1242
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),
1243
true, ROTATION_YAW_90));
1244
}
1245
#endif // AP_COMPASS_LIS3MDL_ENABLED
1246
1247
#if AP_COMPASS_AK09916_ENABLED
1248
// AK09916. This can be found twice, due to the ICM20948 i2c bus pass-thru, so we need to be careful to avoid that
1249
FOREACH_I2C_EXTERNAL(i) {
1250
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
1251
true, ROTATION_YAW_270));
1252
}
1253
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1254
FOREACH_I2C_INTERNAL(i) {
1255
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),
1256
all_external, all_external?ROTATION_YAW_270:ROTATION_NONE));
1257
}
1258
#endif
1259
#endif // AP_COMPASS_AK09916_ENABLED
1260
1261
#if AP_COMPASS_IST8310_ENABLED
1262
// IST8310 on external and internal bus
1263
if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV5 &&
1264
AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV6) {
1265
enum Rotation default_rotation = AP_COMPASS_IST8310_DEFAULT_ROTATION;
1266
1267
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_AEROFC) {
1268
default_rotation = ROTATION_PITCH_180_YAW_90;
1269
}
1270
// probe all 4 possible addresses
1271
const uint8_t ist8310_addr[] = { 0x0C, 0x0D, 0x0E, 0x0F };
1272
1273
for (uint8_t a=0; a<ARRAY_SIZE(ist8310_addr); a++) {
1274
FOREACH_I2C_EXTERNAL(i) {
1275
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),
1276
true, default_rotation));
1277
}
1278
#if !defined(HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE) && !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1279
FOREACH_I2C_INTERNAL(i) {
1280
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),
1281
all_external, default_rotation));
1282
}
1283
#endif
1284
}
1285
}
1286
#endif // AP_COMPASS_IST8310_ENABLED
1287
1288
#if AP_COMPASS_IST8308_ENABLED
1289
// external i2c bus
1290
FOREACH_I2C_EXTERNAL(i) {
1291
ADD_BACKEND(DRIVER_IST8308, AP_Compass_IST8308::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8308_I2C_ADDR),
1292
true, ROTATION_NONE));
1293
}
1294
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1295
FOREACH_I2C_INTERNAL(i) {
1296
ADD_BACKEND(DRIVER_IST8308, AP_Compass_IST8308::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8308_I2C_ADDR),
1297
all_external, ROTATION_NONE));
1298
}
1299
#endif
1300
#endif // AP_COMPASS_IST8308_ENABLED
1301
1302
#if AP_COMPASS_MMC3416_ENABLED
1303
// external i2c bus
1304
FOREACH_I2C_EXTERNAL(i) {
1305
ADD_BACKEND(DRIVER_MMC3416, AP_Compass_MMC3416::probe(GET_I2C_DEVICE(i, HAL_COMPASS_MMC3416_I2C_ADDR),
1306
true, ROTATION_NONE));
1307
}
1308
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1309
FOREACH_I2C_INTERNAL(i) {
1310
ADD_BACKEND(DRIVER_MMC3416, AP_Compass_MMC3416::probe(GET_I2C_DEVICE(i, HAL_COMPASS_MMC3416_I2C_ADDR),
1311
all_external, ROTATION_NONE));
1312
}
1313
#endif
1314
#endif // AP_COMPASS_MMC3416_ENABLED
1315
1316
#if AP_COMPASS_RM3100_ENABLED
1317
#ifdef HAL_COMPASS_RM3100_I2C_ADDR
1318
const uint8_t rm3100_addresses[] = { HAL_COMPASS_RM3100_I2C_ADDR };
1319
#else
1320
// RM3100 can be on 4 different addresses
1321
const uint8_t rm3100_addresses[] = { HAL_COMPASS_RM3100_I2C_ADDR1,
1322
HAL_COMPASS_RM3100_I2C_ADDR2,
1323
HAL_COMPASS_RM3100_I2C_ADDR3,
1324
HAL_COMPASS_RM3100_I2C_ADDR4 };
1325
#endif
1326
// external i2c bus
1327
FOREACH_I2C_EXTERNAL(i) {
1328
for (uint8_t j=0; j<ARRAY_SIZE(rm3100_addresses); j++) {
1329
ADD_BACKEND(DRIVER_RM3100, AP_Compass_RM3100::probe(GET_I2C_DEVICE(i, rm3100_addresses[j]), true, ROTATION_NONE));
1330
}
1331
}
1332
1333
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1334
FOREACH_I2C_INTERNAL(i) {
1335
for (uint8_t j=0; j<ARRAY_SIZE(rm3100_addresses); j++) {
1336
ADD_BACKEND(DRIVER_RM3100, AP_Compass_RM3100::probe(GET_I2C_DEVICE(i, rm3100_addresses[j]), all_external, ROTATION_NONE));
1337
}
1338
}
1339
#endif
1340
#endif // AP_COMPASS_RM3100_ENABLED
1341
1342
#if AP_COMPASS_BMM150_DETECT_BACKENDS_ENABLED
1343
// BMM150 on I2C
1344
FOREACH_I2C_EXTERNAL(i) {
1345
for (uint8_t addr=BMM150_I2C_ADDR_MIN; addr <= BMM150_I2C_ADDR_MAX; addr++) {
1346
ADD_BACKEND(DRIVER_BMM150,
1347
AP_Compass_BMM150::probe(GET_I2C_DEVICE(i, addr), true, ROTATION_NONE));
1348
}
1349
}
1350
#endif // AP_COMPASS_BMM150_ENABLED
1351
1352
#if AP_COMPASS_BMM350_ENABLED
1353
// BMM350 on I2C
1354
FOREACH_I2C_EXTERNAL(i) {
1355
for (uint8_t addr=BMM350_I2C_ADDR_MIN; addr <= BMM350_I2C_ADDR_MAX; addr++) {
1356
ADD_BACKEND(DRIVER_BMM350,
1357
AP_Compass_BMM350::probe(GET_I2C_DEVICE(i, addr), true, ROTATION_NONE));
1358
}
1359
}
1360
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
1361
FOREACH_I2C_INTERNAL(i) {
1362
for (uint8_t addr=BMM350_I2C_ADDR_MIN; addr <= BMM350_I2C_ADDR_MAX; addr++) {
1363
ADD_BACKEND(DRIVER_BMM350, AP_Compass_BMM350::probe(GET_I2C_DEVICE(i, addr), all_external, ROTATION_NONE));
1364
}
1365
}
1366
#endif
1367
#endif // AP_COMPASS_BMM350_ENABLED
1368
}
1369
1370
/*
1371
detect available backends for this board
1372
*/
1373
void Compass::_detect_backends(void)
1374
{
1375
#if AP_COMPASS_EXTERNALAHRS_ENABLED
1376
const int8_t serial_port = AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::COMPASS);
1377
if (serial_port >= 0) {
1378
ADD_BACKEND(DRIVER_EXTERNALAHRS, NEW_NOTHROW AP_Compass_ExternalAHRS(serial_port));
1379
}
1380
#endif
1381
1382
#if AP_FEATURE_BOARD_DETECT
1383
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) {
1384
// default to disabling LIS3MDL on pixhawk2 due to hardware issue
1385
#if AP_COMPASS_LIS3MDL_ENABLED
1386
_driver_type_mask.set_default(1U<<DRIVER_LIS3MDL);
1387
#endif
1388
}
1389
#endif
1390
1391
#if AP_COMPASS_SITL_ENABLED && !AP_TEST_DRONECAN_DRIVERS
1392
ADD_BACKEND(DRIVER_SITL, NEW_NOTHROW AP_Compass_SITL());
1393
#endif
1394
1395
#if AP_COMPASS_DRONECAN_ENABLED
1396
// probe DroneCAN before I2C and SPI so that DroneCAN compasses
1397
// default to first in the list for a new board
1398
probe_dronecan_compasses();
1399
CHECK_UNREG_LIMIT_RETURN;
1400
#endif
1401
1402
#ifdef HAL_PROBE_EXTERNAL_I2C_COMPASSES
1403
// allow boards to ask for external probing of all i2c compass types in hwdef.dat
1404
_probe_external_i2c_compasses();
1405
CHECK_UNREG_LIMIT_RETURN;
1406
#endif
1407
1408
#if AP_COMPASS_MSP_ENABLED
1409
for (uint8_t i=0; i<8; i++) {
1410
if (msp_instance_mask & (1U<<i)) {
1411
ADD_BACKEND(DRIVER_MSP, NEW_NOTHROW AP_Compass_MSP(i));
1412
}
1413
}
1414
#endif
1415
1416
// finally look for i2c and spi compasses not found yet
1417
CHECK_UNREG_LIMIT_RETURN;
1418
probe_i2c_spi_compasses();
1419
1420
if (_backend_count == 0 ||
1421
_compass_count == 0) {
1422
DEV_PRINTF("No Compass backends available\n");
1423
}
1424
}
1425
1426
/*
1427
probe i2c and SPI compasses
1428
*/
1429
void Compass::probe_i2c_spi_compasses(void)
1430
{
1431
#if defined(HAL_MAG_PROBE_LIST)
1432
// driver probes defined by COMPASS lines in hwdef.dat
1433
HAL_MAG_PROBE_LIST;
1434
#elif AP_FEATURE_BOARD_DETECT
1435
switch (AP_BoardConfig::get_board_type()) {
1436
case AP_BoardConfig::PX4_BOARD_PX4V1:
1437
case AP_BoardConfig::PX4_BOARD_PIXHAWK:
1438
case AP_BoardConfig::PX4_BOARD_PHMINI:
1439
case AP_BoardConfig::PX4_BOARD_AUAV21:
1440
case AP_BoardConfig::PX4_BOARD_PH2SLIM:
1441
case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
1442
case AP_BoardConfig::PX4_BOARD_MINDPXV2:
1443
case AP_BoardConfig::PX4_BOARD_FMUV5:
1444
case AP_BoardConfig::PX4_BOARD_FMUV6:
1445
case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
1446
case AP_BoardConfig::PX4_BOARD_AEROFC:
1447
_probe_external_i2c_compasses();
1448
CHECK_UNREG_LIMIT_RETURN;
1449
break;
1450
1451
case AP_BoardConfig::PX4_BOARD_PCNC1:
1452
#if AP_COMPASS_BMM150_ENABLED
1453
ADD_BACKEND(DRIVER_BMM150,
1454
AP_Compass_BMM150::probe(GET_I2C_DEVICE(0, 0x10), false, ROTATION_NONE));
1455
#endif
1456
break;
1457
case AP_BoardConfig::VRX_BOARD_BRAIN54:
1458
case AP_BoardConfig::VRX_BOARD_BRAIN51: {
1459
#if AP_COMPASS_HMC5843_ENABLED
1460
// external i2c bus
1461
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),
1462
true, ROTATION_ROLL_180));
1463
1464
// internal i2c bus
1465
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),
1466
false, ROTATION_YAW_270));
1467
#endif // AP_COMPASS_HMC5843_ENABLED
1468
}
1469
break;
1470
1471
case AP_BoardConfig::VRX_BOARD_BRAIN52:
1472
case AP_BoardConfig::VRX_BOARD_BRAIN52E:
1473
case AP_BoardConfig::VRX_BOARD_CORE10:
1474
case AP_BoardConfig::VRX_BOARD_UBRAIN51:
1475
case AP_BoardConfig::VRX_BOARD_UBRAIN52: {
1476
#if AP_COMPASS_HMC5843_ENABLED
1477
// external i2c bus
1478
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),
1479
true, ROTATION_ROLL_180));
1480
#endif // AP_COMPASS_HMC5843_ENABLED
1481
}
1482
break;
1483
1484
default:
1485
break;
1486
}
1487
switch (AP_BoardConfig::get_board_type()) {
1488
case AP_BoardConfig::PX4_BOARD_PIXHAWK:
1489
#if AP_COMPASS_HMC5843_ENABLED
1490
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(hal.spi->get_device(HAL_COMPASS_HMC5843_NAME),
1491
false, ROTATION_PITCH_180));
1492
#endif
1493
#if AP_COMPASS_LSM303D_ENABLED
1494
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_NONE));
1495
#endif
1496
break;
1497
1498
case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
1499
#if AP_COMPASS_LSM303D_ENABLED
1500
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270));
1501
#endif
1502
#if AP_COMPASS_AK8963_ENABLED
1503
// we run the AK8963 only on the 2nd MPU9250, which leaves the
1504
// first MPU9250 to run without disturbance at high rate
1505
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_YAW_270));
1506
#endif
1507
#if AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED
1508
ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_ROLL_180_YAW_90));
1509
#endif
1510
break;
1511
1512
case AP_BoardConfig::PX4_BOARD_FMUV5:
1513
case AP_BoardConfig::PX4_BOARD_FMUV6:
1514
#if AP_COMPASS_IST8310_ENABLED
1515
FOREACH_I2C_EXTERNAL(i) {
1516
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
1517
true, ROTATION_ROLL_180_YAW_90));
1518
}
1519
FOREACH_I2C_INTERNAL(i) {
1520
ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),
1521
false, ROTATION_ROLL_180_YAW_90));
1522
}
1523
#endif // AP_COMPASS_IST8310_ENABLED
1524
break;
1525
1526
case AP_BoardConfig::PX4_BOARD_SP01:
1527
#if AP_COMPASS_AK8963_ENABLED
1528
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_NONE));
1529
#endif
1530
break;
1531
1532
case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
1533
#if AP_COMPASS_AK8963_ENABLED
1534
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));
1535
#endif
1536
#if AP_COMPASS_LIS3MDL_ENABLED
1537
ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME),
1538
false, ROTATION_NONE));
1539
#endif // AP_COMPASS_LIS3MDL_ENABLED
1540
break;
1541
1542
case AP_BoardConfig::PX4_BOARD_PHMINI:
1543
#if AP_COMPASS_AK8963_ENABLED
1544
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180));
1545
#endif
1546
break;
1547
1548
case AP_BoardConfig::PX4_BOARD_AUAV21:
1549
#if AP_COMPASS_AK8963_ENABLED
1550
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));
1551
#endif
1552
break;
1553
1554
case AP_BoardConfig::PX4_BOARD_PH2SLIM:
1555
#if AP_COMPASS_AK8963_ENABLED
1556
ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_YAW_270));
1557
#endif
1558
break;
1559
1560
case AP_BoardConfig::PX4_BOARD_MINDPXV2:
1561
#if AP_COMPASS_HMC5843_ENABLED
1562
ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),
1563
false, ROTATION_YAW_90));
1564
#endif
1565
#if AP_COMPASS_LSM303D_ENABLED
1566
ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_PITCH_180_YAW_270));
1567
#endif
1568
break;
1569
1570
default:
1571
break;
1572
}
1573
#endif
1574
}
1575
1576
#if AP_COMPASS_DRONECAN_ENABLED
1577
/*
1578
look for DroneCAN compasses
1579
*/
1580
void Compass::probe_dronecan_compasses(void)
1581
{
1582
if (!_driver_enabled(DRIVER_UAVCAN)) {
1583
return;
1584
}
1585
for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {
1586
AP_Compass_Backend* _uavcan_backend = AP_Compass_DroneCAN::probe(i);
1587
if (_uavcan_backend) {
1588
_add_backend(_uavcan_backend);
1589
}
1590
#if COMPASS_MAX_UNREG_DEV > 0
1591
if (_unreg_compass_count == COMPASS_MAX_UNREG_DEV) {
1592
break;
1593
}
1594
#endif
1595
}
1596
1597
#if COMPASS_MAX_UNREG_DEV > 0
1598
if (option_set(Option::ALLOW_DRONECAN_AUTO_REPLACEMENT) && !suppress_devid_save) {
1599
// check if there's any uavcan compass in prio slot that's not found
1600
// and replace it if there's a replacement compass
1601
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
1602
if (AP_HAL::Device::devid_get_bus_type(_priority_did_list[i]) != AP_HAL::Device::BUS_TYPE_UAVCAN
1603
|| _get_state(i).registered) {
1604
continue;
1605
}
1606
// There's a UAVCAN compass missing
1607
// Let's check if there's a replacement
1608
for (uint8_t j=0; j<COMPASS_MAX_INSTANCES; j++) {
1609
uint32_t detected_devid = AP_Compass_DroneCAN::get_detected_devid(j);
1610
// Check if this is a potential replacement mag
1611
if (!is_replacement_mag(detected_devid)) {
1612
continue;
1613
}
1614
// We have found a replacement mag, let's replace the existing one
1615
// with this by setting the priority to zero and calling uavcan probe
1616
GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Mag: Compass #%d with DEVID %lu replaced", uint8_t(i), (unsigned long)_priority_did_list[i]);
1617
_priority_did_stored_list[i].set_and_save(0);
1618
_priority_did_list[i] = 0;
1619
1620
AP_Compass_Backend* _uavcan_backend = AP_Compass_DroneCAN::probe(j);
1621
if (_uavcan_backend) {
1622
_add_backend(_uavcan_backend);
1623
// we also need to remove the id from unreg list
1624
remove_unreg_dev_id(detected_devid);
1625
} else {
1626
// the mag has already been allocated,
1627
// let's begin the replacement
1628
bool found_replacement = false;
1629
for (StateIndex k(0); k<COMPASS_MAX_INSTANCES; k++) {
1630
if ((uint32_t)_state[k].dev_id == detected_devid) {
1631
if (_state[k].priority <= uint8_t(i)) {
1632
// we are already on higher priority
1633
// nothing to do
1634
break;
1635
}
1636
found_replacement = true;
1637
// reset old priority of replacement mag
1638
_priority_did_stored_list[_state[k].priority].set_and_save(0);
1639
_priority_did_list[_state[k].priority] = 0;
1640
// update new priority
1641
_state[k].priority = i;
1642
}
1643
}
1644
if (!found_replacement) {
1645
continue;
1646
}
1647
_priority_did_stored_list[i].set_and_save(detected_devid);
1648
_priority_did_list[i] = detected_devid;
1649
}
1650
}
1651
}
1652
}
1653
#endif // #if COMPASS_MAX_UNREG_DEV > 0
1654
}
1655
#endif // AP_COMPASS_DRONECAN_ENABLED
1656
1657
1658
// Check if the devid is a potential replacement compass
1659
// Following are the checks done to ensure the compass is a replacement
1660
// * The compass is an UAVCAN compass
1661
// * The compass wasn't seen before this boot as additional unreg mag
1662
// * The compass might have been seen before but never setup
1663
bool Compass::is_replacement_mag(uint32_t devid) {
1664
#if COMPASS_MAX_INSTANCES > 1
1665
// We only do this for UAVCAN mag
1666
if (devid == 0 || (AP_HAL::Device::devid_get_bus_type(devid) != AP_HAL::Device::BUS_TYPE_UAVCAN)) {
1667
return false;
1668
}
1669
1670
#if COMPASS_MAX_UNREG_DEV > 0
1671
// Check that its not an unused additional mag
1672
for (uint8_t i = 0; i<COMPASS_MAX_UNREG_DEV; i++) {
1673
if (_previously_unreg_mag[i] == devid) {
1674
return false;
1675
}
1676
}
1677
#endif
1678
1679
// Check that its not previously setup mag
1680
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
1681
if ((uint32_t)_state[i].expected_dev_id == devid) {
1682
return false;
1683
}
1684
}
1685
#endif
1686
return true;
1687
}
1688
1689
void Compass::remove_unreg_dev_id(uint32_t devid)
1690
{
1691
#if COMPASS_MAX_INSTANCES > 1
1692
// We only do this for UAVCAN mag
1693
if (devid == 0 || (AP_HAL::Device::devid_get_bus_type(devid) != AP_HAL::Device::BUS_TYPE_UAVCAN)) {
1694
return;
1695
}
1696
1697
#if COMPASS_MAX_UNREG_DEV > 0
1698
for (uint8_t i = 0; i<COMPASS_MAX_UNREG_DEV; i++) {
1699
if ((uint32_t)extra_dev_id[i] == devid) {
1700
extra_dev_id[i].set(0);
1701
return;
1702
}
1703
}
1704
#endif
1705
#endif
1706
}
1707
1708
void Compass::_reset_compass_id()
1709
{
1710
#if COMPASS_MAX_INSTANCES > 1
1711
// Check if any of the registered devs are not registered
1712
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
1713
if (_priority_did_stored_list[i] != _priority_did_list[i] ||
1714
_priority_did_stored_list[i] == 0) {
1715
//We don't touch priorities that might have been touched by the user
1716
continue;
1717
}
1718
if (!_get_state(i).registered) {
1719
_priority_did_stored_list[i].set_and_save(0);
1720
GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Mag: Compass #%d with DEVID %lu removed", uint8_t(i), (unsigned long)_priority_did_list[i]);
1721
}
1722
}
1723
1724
// Check if any of the old registered devs are not registered
1725
// and hence can be removed
1726
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
1727
if (_state[i].dev_id == 0 && _state[i].expected_dev_id != 0) {
1728
// also hard reset dev_ids that are not detected
1729
_state[i].dev_id.save();
1730
}
1731
}
1732
#endif
1733
}
1734
1735
// Look for devices beyond initialisation
1736
void
1737
Compass::_detect_runtime(void)
1738
{
1739
#if AP_COMPASS_DRONECAN_ENABLED
1740
if (!available()) {
1741
return;
1742
}
1743
1744
//Don't try to add device while armed
1745
if (hal.util->get_soft_armed()) {
1746
return;
1747
}
1748
static uint32_t last_try;
1749
//Try once every second
1750
if ((AP_HAL::millis() - last_try) < 1000) {
1751
return;
1752
}
1753
last_try = AP_HAL::millis();
1754
if (_driver_enabled(DRIVER_UAVCAN)) {
1755
for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {
1756
AP_Compass_Backend* _uavcan_backend = AP_Compass_DroneCAN::probe(i);
1757
if (_uavcan_backend) {
1758
_add_backend(_uavcan_backend);
1759
}
1760
CHECK_UNREG_LIMIT_RETURN;
1761
}
1762
}
1763
#endif // AP_COMPASS_DRONECAN_ENABLED
1764
}
1765
1766
bool
1767
Compass::read(void)
1768
{
1769
if (!available()) {
1770
return false;
1771
}
1772
1773
#if HAL_LOGGING_ENABLED
1774
const bool old_healthy = healthy();
1775
#endif
1776
1777
#ifndef HAL_BUILD_AP_PERIPH
1778
if (!_initial_location_set) {
1779
try_set_initial_location();
1780
}
1781
#endif
1782
1783
_detect_runtime();
1784
1785
for (uint8_t i=0; i< _backend_count; i++) {
1786
// call read on each of the backend. This call updates field[i]
1787
_backends[i]->read();
1788
}
1789
uint32_t time = AP_HAL::millis();
1790
bool any_healthy = false;
1791
for (StateIndex i(0); i < COMPASS_MAX_INSTANCES; i++) {
1792
_state[i].healthy = (time - _state[i].last_update_ms < 500);
1793
any_healthy |= _state[i].healthy;
1794
}
1795
#if COMPASS_LEARN_ENABLED
1796
if (_learn == LEARN_INFLIGHT && !learn_allocated) {
1797
learn_allocated = true;
1798
learn = NEW_NOTHROW CompassLearn(*this);
1799
}
1800
if (_learn == LEARN_INFLIGHT && learn != nullptr) {
1801
learn->update();
1802
}
1803
#endif
1804
#if HAL_LOGGING_ENABLED
1805
if (any_healthy && _log_bit != (uint32_t)-1 && AP::logger().should_log(_log_bit)) {
1806
AP::logger().Write_Compass();
1807
}
1808
#endif
1809
1810
// Set _first_usable parameter
1811
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
1812
if (_use_for_yaw[i]) {
1813
_first_usable = uint8_t(i);
1814
break;
1815
}
1816
}
1817
const bool new_healthy = healthy();
1818
1819
#if HAL_LOGGING_ENABLED
1820
1821
#define MASK_LOG_ANY 0xFFFF
1822
1823
if (new_healthy != old_healthy) {
1824
if (AP::logger().should_log(MASK_LOG_ANY)) {
1825
const LogErrorCode code = new_healthy ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY;
1826
AP::logger().Write_Error(LogErrorSubsystem::COMPASS, code);
1827
}
1828
}
1829
#endif
1830
1831
return new_healthy;
1832
}
1833
1834
uint8_t
1835
Compass::get_healthy_mask() const
1836
{
1837
uint8_t healthy_mask = 0;
1838
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
1839
if (healthy(uint8_t(i))) {
1840
healthy_mask |= 1 << uint8_t(i);
1841
}
1842
}
1843
return healthy_mask;
1844
}
1845
1846
void
1847
Compass::set_offsets(uint8_t i, const Vector3f &offsets)
1848
{
1849
// sanity check compass instance provided
1850
StateIndex id = _get_state_id(Priority(i));
1851
if (id < COMPASS_MAX_INSTANCES) {
1852
_state[id].offset.set(offsets);
1853
}
1854
}
1855
1856
void
1857
Compass::set_and_save_offsets(uint8_t i, const Vector3f &offsets)
1858
{
1859
// sanity check compass instance provided
1860
StateIndex id = _get_state_id(Priority(i));
1861
if (id < COMPASS_MAX_INSTANCES) {
1862
_state[id].offset.set(offsets);
1863
save_offsets(i);
1864
}
1865
}
1866
1867
#if AP_COMPASS_DIAGONALS_ENABLED
1868
void
1869
Compass::set_and_save_diagonals(uint8_t i, const Vector3f &diagonals)
1870
{
1871
// sanity check compass instance provided
1872
StateIndex id = _get_state_id(Priority(i));
1873
if (id < COMPASS_MAX_INSTANCES) {
1874
_state[id].diagonals.set_and_save(diagonals);
1875
}
1876
}
1877
1878
void
1879
Compass::set_and_save_offdiagonals(uint8_t i, const Vector3f &offdiagonals)
1880
{
1881
// sanity check compass instance provided
1882
StateIndex id = _get_state_id(Priority(i));
1883
if (id < COMPASS_MAX_INSTANCES) {
1884
_state[id].offdiagonals.set_and_save(offdiagonals);
1885
}
1886
}
1887
#endif // AP_COMPASS_DIAGONALS_ENABLED
1888
1889
void
1890
Compass::set_and_save_scale_factor(uint8_t i, float scale_factor)
1891
{
1892
StateIndex id = _get_state_id(Priority(i));
1893
if (i < COMPASS_MAX_INSTANCES) {
1894
_state[id].scale_factor.set_and_save(scale_factor);
1895
}
1896
}
1897
1898
void
1899
Compass::save_offsets(uint8_t i)
1900
{
1901
StateIndex id = _get_state_id(Priority(i));
1902
if (id < COMPASS_MAX_INSTANCES) {
1903
_state[id].offset.save(); // save offsets
1904
_state[id].dev_id.set_and_save(_state[id].detected_dev_id);
1905
}
1906
}
1907
1908
void
1909
Compass::set_and_save_orientation(uint8_t i, Rotation orientation)
1910
{
1911
StateIndex id = _get_state_id(Priority(i));
1912
if (id < COMPASS_MAX_INSTANCES) {
1913
_state[id].orientation.set_and_save_ifchanged(orientation);
1914
}
1915
}
1916
1917
void
1918
Compass::save_offsets(void)
1919
{
1920
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
1921
save_offsets(uint8_t(i));
1922
}
1923
}
1924
1925
void
1926
Compass::set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor)
1927
{
1928
StateIndex id = _get_state_id(Priority(i));
1929
if (id < COMPASS_MAX_INSTANCES) {
1930
_state[id].motor_compensation.set(motor_comp_factor);
1931
}
1932
}
1933
1934
void
1935
Compass::save_motor_compensation()
1936
{
1937
StateIndex id;
1938
_motor_comp_type.save();
1939
for (Priority k(0); k<COMPASS_MAX_INSTANCES; k++) {
1940
id = _get_state_id(k);
1941
if (id<COMPASS_MAX_INSTANCES) {
1942
_state[id].motor_compensation.save();
1943
}
1944
}
1945
}
1946
1947
void Compass::try_set_initial_location()
1948
{
1949
if (!_auto_declination) {
1950
return;
1951
}
1952
if (!_enabled) {
1953
return;
1954
}
1955
1956
Location loc;
1957
if (!AP::ahrs().get_location(loc)) {
1958
return;
1959
}
1960
_initial_location_set = true;
1961
1962
// if automatic declination is configured, then compute
1963
// the declination based on the initial GPS fix
1964
// Set the declination based on the lat/lng from GPS
1965
_declination.set(radians(
1966
AP_Declination::get_declination(
1967
(float)loc.lat / 10000000,
1968
(float)loc.lng / 10000000)));
1969
}
1970
1971
/// return true if the compass should be used for yaw calculations
1972
bool
1973
Compass::use_for_yaw(void) const
1974
{
1975
return healthy(_first_usable) && use_for_yaw(_first_usable);
1976
}
1977
1978
/// return true if the specified compass can be used for yaw calculations
1979
bool
1980
Compass::use_for_yaw(uint8_t i) const
1981
{
1982
if (!available()) {
1983
return false;
1984
}
1985
// when we are doing in-flight compass learning the state
1986
// estimator must not use the compass. The learning code turns off
1987
// inflight learning when it has converged
1988
return _use_for_yaw[Priority(i)] && _learn.get() != LEARN_INFLIGHT;
1989
}
1990
1991
/*
1992
return the number of enabled sensors. Used to determine if
1993
non-compass operation is desired
1994
*/
1995
uint8_t Compass::get_num_enabled(void) const
1996
{
1997
if (get_count() == 0) {
1998
return 0;
1999
}
2000
uint8_t count = 0;
2001
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
2002
if (use_for_yaw(i)) {
2003
count++;
2004
}
2005
}
2006
return count;
2007
}
2008
2009
void
2010
Compass::set_declination(float radians, bool save_to_eeprom)
2011
{
2012
if (save_to_eeprom) {
2013
_declination.set_and_save(radians);
2014
} else {
2015
_declination.set(radians);
2016
}
2017
}
2018
2019
float
2020
Compass::get_declination() const
2021
{
2022
return _declination.get();
2023
}
2024
2025
/*
2026
calculate a compass heading given the attitude from DCM and the mag vector
2027
*/
2028
float
2029
Compass::calculate_heading(const Matrix3f &dcm_matrix, uint8_t i) const
2030
{
2031
/*
2032
This extracts a roll/pitch-only rotation which is then used to rotate the body frame field into earth frame so the heading can be calculated.
2033
One could do:
2034
float roll, pitch, yaw;
2035
dcm_matrix.to_euler(roll, pitch, yaw)
2036
Matrix3f rp_rot;
2037
rp_rot.from_euler(roll, pitch, 0)
2038
Vector3f ef = rp_rot * field
2039
2040
Because only the X and Y components are needed it's more efficient to manually calculate:
2041
2042
rp_rot = [ cos(pitch), sin(roll) * sin(pitch), cos(roll) * sin(pitch)
2043
0, cos(roll), -sin(roll)]
2044
2045
If the whole matrix is multiplied by cos(pitch) the required trigonometric values can be extracted directly from the existing dcm matrix.
2046
This multiplication has no effect on the calculated heading as it changes the length of the North/East vector but not its angle.
2047
2048
rp_rot = [ cos(pitch)^2, sin(roll) * sin(pitch) * cos(pitch), cos(roll) * sin(pitch) * cos(pitch)
2049
0, cos(roll) * cos(pitch), -sin(roll) * cos(pitch)]
2050
2051
Preexisting values can be substituted in:
2052
2053
dcm_matrix.c.x = -sin(pitch)
2054
dcm_matrix.c.y = sin(roll) * cos(pitch)
2055
dcm_matrix.c.z = cos(roll) * cos(pitch)
2056
2057
rp_rot = [ cos(pitch)^2, dcm_matrix.c.y * -dcm_matrix.c.x, dcm_matrix.c.z * -dcm_matrix.c.x
2058
0, dcm_matrix.c.z, -dcm_matrix.c.y]
2059
2060
cos(pitch)^2 is stil needed. This is the same as 1 - sin(pitch)^2.
2061
sin(pitch) is avalable as dcm_matrix.c.x
2062
*/
2063
2064
const float cos_pitch_sq = 1.0f-(dcm_matrix.c.x*dcm_matrix.c.x);
2065
2066
// Tilt compensated magnetic field Y component:
2067
const Vector3f &field = get_field(i);
2068
2069
const float headY = field.y * dcm_matrix.c.z - field.z * dcm_matrix.c.y;
2070
2071
// Tilt compensated magnetic field X component:
2072
const float headX = field.x * cos_pitch_sq - dcm_matrix.c.x * (field.y * dcm_matrix.c.y + field.z * dcm_matrix.c.z);
2073
2074
// magnetic heading
2075
// 6/4/11 - added constrain to keep bad values from ruining DCM Yaw - Jason S.
2076
const float heading = constrain_float(atan2f(-headY,headX), -M_PI, M_PI);
2077
2078
// Declination correction
2079
return wrap_PI(heading + _declination);
2080
}
2081
2082
/// Returns True if the compasses have been configured (i.e. offsets saved)
2083
///
2084
/// @returns True if compass has been configured
2085
///
2086
bool Compass::configured(uint8_t i)
2087
{
2088
// exit immediately if instance is beyond the number of compasses we have available
2089
if (i > get_count()) {
2090
return false;
2091
}
2092
2093
// exit immediately if all offsets are zero
2094
if (is_zero(get_offsets(i).length())) {
2095
return false;
2096
}
2097
2098
StateIndex id = _get_state_id(Priority(i));
2099
// exit immediately if dev_id hasn't been detected
2100
if (_state[id].detected_dev_id == 0 ||
2101
id == COMPASS_MAX_INSTANCES) {
2102
return false;
2103
}
2104
2105
#ifdef HAL_USE_EMPTY_STORAGE
2106
// the load() call below returns zeroes on empty storage, so the
2107
// check-stored-value check here will always fail. Since nobody
2108
// really cares about the empty-storage case, shortcut out here
2109
// for simplicity.
2110
return true;
2111
#endif
2112
2113
// back up cached value of dev_id
2114
int32_t dev_id_cache_value = _state[id].dev_id;
2115
2116
// load dev_id from eeprom
2117
_state[id].dev_id.load();
2118
2119
// if dev_id loaded from eeprom is different from detected dev id or dev_id loaded from eeprom is different from cached dev_id, compass is unconfigured
2120
if (_state[id].dev_id != _state[id].detected_dev_id || _state[id].dev_id != dev_id_cache_value) {
2121
// restore cached value
2122
_state[id].dev_id.set(dev_id_cache_value);
2123
// return failure
2124
return false;
2125
}
2126
2127
// if we got here then it must be configured
2128
return true;
2129
}
2130
2131
bool Compass::configured(char *failure_msg, uint8_t failure_msg_len)
2132
{
2133
#if COMPASS_MAX_INSTANCES > 1
2134
// Check if any of the registered devs are not registered
2135
for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {
2136
if (_priority_did_list[i] != 0 && use_for_yaw(uint8_t(i))) {
2137
if (!_get_state(i).registered) {
2138
snprintf(failure_msg, failure_msg_len, "Compass %d not found", uint8_t(i + 1));
2139
return false;
2140
}
2141
if (_priority_did_list[i] != _priority_did_stored_list[i]) {
2142
snprintf(failure_msg, failure_msg_len, "Compass order change requires reboot");
2143
return false;
2144
}
2145
}
2146
}
2147
#endif
2148
2149
bool all_configured = true;
2150
for (uint8_t i=0; i<get_count(); i++) {
2151
if (configured(i)) {
2152
continue;
2153
}
2154
if (!use_for_yaw(i)) {
2155
// we're not planning on using this anyway so sure,
2156
// whatever, it's configured....
2157
continue;
2158
}
2159
all_configured = false;
2160
break;
2161
}
2162
if (!all_configured) {
2163
snprintf(failure_msg, failure_msg_len, "Compass not calibrated");
2164
}
2165
return all_configured;
2166
}
2167
2168
/*
2169
set the type of motor compensation to use
2170
*/
2171
void Compass::motor_compensation_type(const uint8_t comp_type)
2172
{
2173
if (_motor_comp_type <= AP_COMPASS_MOT_COMP_CURRENT && _motor_comp_type != (int8_t)comp_type) {
2174
_motor_comp_type.set((int8_t)comp_type);
2175
_thr = 0; // set current throttle to zero
2176
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
2177
set_motor_compensation(i, Vector3f(0,0,0)); // clear out invalid compensation vectors
2178
}
2179
}
2180
}
2181
2182
bool Compass::consistent() const
2183
{
2184
const Vector3f &primary_mag_field { get_field() };
2185
const Vector2f &primary_mag_field_xy { primary_mag_field.xy() };
2186
2187
for (uint8_t i=0; i<get_count(); i++) {
2188
if (!use_for_yaw(i)) {
2189
// configured not-to-be-used
2190
continue;
2191
}
2192
2193
const Vector3f &mag_field = get_field(i);
2194
const Vector2f &mag_field_xy = mag_field.xy();
2195
2196
if (mag_field_xy.is_zero()) {
2197
return false;
2198
}
2199
2200
// check for gross misalignment on all axes
2201
const float xyz_ang_diff = mag_field.angle(primary_mag_field);
2202
if (xyz_ang_diff > AP_COMPASS_MAX_XYZ_ANG_DIFF) {
2203
return false;
2204
}
2205
2206
// check for an unacceptable angle difference on the xy plane
2207
const float xy_ang_diff = mag_field_xy.angle(primary_mag_field_xy);
2208
if (xy_ang_diff > AP_COMPASS_MAX_XY_ANG_DIFF) {
2209
return false;
2210
}
2211
2212
// check for an unacceptable length difference on the xy plane
2213
const float xy_len_diff = (primary_mag_field_xy-mag_field_xy).length();
2214
if (xy_len_diff > AP_COMPASS_MAX_XY_LENGTH_DIFF) {
2215
return false;
2216
}
2217
}
2218
return true;
2219
}
2220
2221
bool Compass::healthy(uint8_t i) const
2222
{
2223
return (i < COMPASS_MAX_INSTANCES) ? _get_state(Priority(i)).healthy : false;
2224
}
2225
2226
/*
2227
return true if we have a valid scale factor
2228
*/
2229
bool Compass::have_scale_factor(uint8_t i) const
2230
{
2231
if (!available()) {
2232
return false;
2233
}
2234
StateIndex id = _get_state_id(Priority(i));
2235
if (id >= COMPASS_MAX_INSTANCES ||
2236
_state[id].scale_factor < COMPASS_MIN_SCALE_FACTOR ||
2237
_state[id].scale_factor > COMPASS_MAX_SCALE_FACTOR) {
2238
return false;
2239
}
2240
return true;
2241
}
2242
2243
#if AP_COMPASS_MSP_ENABLED
2244
void Compass::handle_msp(const MSP::msp_compass_data_message_t &pkt)
2245
{
2246
if (!_driver_enabled(DRIVER_MSP)) {
2247
return;
2248
}
2249
if (!init_done) {
2250
if (pkt.instance < 8) {
2251
msp_instance_mask |= 1U<<pkt.instance;
2252
}
2253
} else {
2254
for (uint8_t i=0; i<_backend_count; i++) {
2255
_backends[i]->handle_msp(pkt);
2256
}
2257
}
2258
}
2259
#endif // AP_COMPASS_MSP_ENABLED
2260
2261
#if AP_COMPASS_EXTERNALAHRS_ENABLED
2262
void Compass::handle_external(const AP_ExternalAHRS::mag_data_message_t &pkt)
2263
{
2264
if (!_driver_enabled(DRIVER_EXTERNALAHRS)) {
2265
return;
2266
}
2267
for (uint8_t i=0; i<_backend_count; i++) {
2268
_backends[i]->handle_external(pkt);
2269
}
2270
}
2271
#endif // AP_COMPASS_EXTERNALAHRS_ENABLED
2272
2273
// force save of current calibration as valid
2274
void Compass::force_save_calibration(void)
2275
{
2276
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
2277
if (_state[i].dev_id != 0) {
2278
_state[i].dev_id.save();
2279
}
2280
}
2281
}
2282
2283
// singleton instance
2284
Compass *Compass::_singleton;
2285
2286
namespace AP
2287
{
2288
2289
Compass &compass()
2290
{
2291
return *Compass::get_singleton();
2292
}
2293
2294
}
2295
2296
#endif // AP_COMPASS_ENABLED
2297
2298