APM:Libraries
AP_Compass.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
4 #endif
7 
8 #include "AP_Compass_SITL.h"
9 #include "AP_Compass_AK8963.h"
10 #include "AP_Compass_Backend.h"
11 #include "AP_Compass_BMM150.h"
12 #include "AP_Compass_HIL.h"
13 #include "AP_Compass_HMC5843.h"
14 #include "AP_Compass_IST8310.h"
15 #include "AP_Compass_LSM303D.h"
16 #include "AP_Compass_LSM9DS1.h"
17 #include "AP_Compass_LIS3MDL.h"
18 #include "AP_Compass_AK09916.h"
19 #include "AP_Compass_QMC5883L.h"
20 #if HAL_WITH_UAVCAN
22 #include "AP_Compass_UAVCAN.h"
23 #endif
24 #include "AP_Compass_MMC3416.h"
25 #include "AP_Compass_MAG3110.h"
26 #include "AP_Compass.h"
27 
28 extern AP_HAL::HAL& hal;
29 
30 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
31 #define COMPASS_LEARN_DEFAULT Compass::LEARN_NONE
32 #else
33 #define COMPASS_LEARN_DEFAULT Compass::LEARN_INTERNAL
34 #endif
35 
36 #ifndef AP_COMPASS_OFFSETS_MAX_DEFAULT
37 #define AP_COMPASS_OFFSETS_MAX_DEFAULT 850
38 #endif
39 
40 #ifndef HAL_COMPASS_FILTER_DEFAULT
41  #define HAL_COMPASS_FILTER_DEFAULT 0 // turned off by default
42 #endif
43 
45  // index 0 was used for the old orientation matrix
46 
47  // @Param: OFS_X
48  // @DisplayName: Compass offsets in milligauss on the X axis
49  // @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame
50  // @Range: -400 400
51  // @Units: mGauss
52  // @Increment: 1
53  // @User: Advanced
54 
55  // @Param: OFS_Y
56  // @DisplayName: Compass offsets in milligauss on the Y axis
57  // @Description: Offset to be added to the compass y-axis values to compensate for metal in the frame
58  // @Range: -400 400
59  // @Units: mGauss
60  // @Increment: 1
61  // @User: Advanced
62 
63  // @Param: OFS_Z
64  // @DisplayName: Compass offsets in milligauss on the Z axis
65  // @Description: Offset to be added to the compass z-axis values to compensate for metal in the frame
66  // @Range: -400 400
67  // @Units: mGauss
68  // @Increment: 1
69  // @User: Advanced
70  AP_GROUPINFO("OFS", 1, Compass, _state[0].offset, 0),
71 
72  // @Param: DEC
73  // @DisplayName: Compass declination
74  // @Description: An angle to compensate between the true north and magnetic north
75  // @Range: -3.142 3.142
76  // @Units: rad
77  // @Increment: 0.01
78  // @User: Standard
79  AP_GROUPINFO("DEC", 2, Compass, _declination, 0),
80 
81  // @Param: LEARN
82  // @DisplayName: Learn compass offsets automatically
83  // @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.
84  // @Values: 0:Disabled,1:Internal-Learning,2:EKF-Learning
85  // @User: Advanced
86  AP_GROUPINFO("LEARN", 3, Compass, _learn, COMPASS_LEARN_DEFAULT),
87 
88  // @Param: USE
89  // @DisplayName: Use compass for yaw
90  // @Description: Enable or disable the use of the compass (instead of the GPS) for determining heading
91  // @Values: 0:Disabled,1:Enabled
92  // @User: Advanced
93  AP_GROUPINFO("USE", 4, Compass, _state[0].use_for_yaw, 1), // true if used for DCM yaw
94 
95  // @Param: AUTODEC
96  // @DisplayName: Auto Declination
97  // @Description: Enable or disable the automatic calculation of the declination based on gps location
98  // @Values: 0:Disabled,1:Enabled
99  // @User: Advanced
100  AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination, 1),
101 
102  // @Param: MOTCT
103  // @DisplayName: Motor interference compensation type
104  // @Description: Set motor interference compensation type to disabled, throttle or current. Do not change manually.
105  // @Values: 0:Disabled,1:Use Throttle,2:Use Current
106  // @User: Advanced
107  AP_GROUPINFO("MOTCT", 6, Compass, _motor_comp_type, AP_COMPASS_MOT_COMP_DISABLED),
108 
109  // @Param: MOT_X
110  // @DisplayName: Motor interference compensation for body frame X axis
111  // @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)
112  // @Range: -1000 1000
113  // @Units: mGauss/A
114  // @Increment: 1
115  // @User: Advanced
116 
117  // @Param: MOT_Y
118  // @DisplayName: Motor interference compensation for body frame Y axis
119  // @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)
120  // @Range: -1000 1000
121  // @Units: mGauss/A
122  // @Increment: 1
123  // @User: Advanced
124 
125  // @Param: MOT_Z
126  // @DisplayName: Motor interference compensation for body frame Z axis
127  // @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)
128  // @Range: -1000 1000
129  // @Units: mGauss/A
130  // @Increment: 1
131  // @User: Advanced
132  AP_GROUPINFO("MOT", 7, Compass, _state[0].motor_compensation, 0),
133 
134  // @Param: ORIENT
135  // @DisplayName: Compass orientation
136  // @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.
137  // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw135,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315
138  // @User: Advanced
139  AP_GROUPINFO("ORIENT", 8, Compass, _state[0].orientation, ROTATION_NONE),
140 
141  // @Param: EXTERNAL
142  // @DisplayName: Compass is attached via an external cable
143  // @Description: Configure compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. 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.
144  // @Values: 0:Internal,1:External,2:ForcedExternal
145  // @User: Advanced
146  AP_GROUPINFO("EXTERNAL", 9, Compass, _state[0].external, 0),
147 
148  // @Param: OFS2_X
149  // @DisplayName: Compass2 offsets in milligauss on the X axis
150  // @Description: Offset to be added to compass2's x-axis values to compensate for metal in the frame
151  // @Range: -400 400
152  // @Units: mGauss
153  // @Increment: 1
154  // @User: Advanced
155 
156  // @Param: OFS2_Y
157  // @DisplayName: Compass2 offsets in milligauss on the Y axis
158  // @Description: Offset to be added to compass2's y-axis values to compensate for metal in the frame
159  // @Range: -400 400
160  // @Units: mGauss
161  // @Increment: 1
162  // @User: Advanced
163 
164  // @Param: OFS2_Z
165  // @DisplayName: Compass2 offsets in milligauss on the Z axis
166  // @Description: Offset to be added to compass2's z-axis values to compensate for metal in the frame
167  // @Range: -400 400
168  // @Units: mGauss
169  // @Increment: 1
170  // @User: Advanced
171  AP_GROUPINFO("OFS2", 10, Compass, _state[1].offset, 0),
172 
173  // @Param: MOT2_X
174  // @DisplayName: Motor interference compensation to compass2 for body frame X axis
175  // @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)
176  // @Range: -1000 1000
177  // @Units: mGauss/A
178  // @Increment: 1
179  // @User: Advanced
180 
181  // @Param: MOT2_Y
182  // @DisplayName: Motor interference compensation to compass2 for body frame Y axis
183  // @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)
184  // @Range: -1000 1000
185  // @Units: mGauss/A
186  // @Increment: 1
187  // @User: Advanced
188 
189  // @Param: MOT2_Z
190  // @DisplayName: Motor interference compensation to compass2 for body frame Z axis
191  // @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)
192  // @Range: -1000 1000
193  // @Units: mGauss/A
194  // @Increment: 1
195  // @User: Advanced
196  AP_GROUPINFO("MOT2", 11, Compass, _state[1].motor_compensation, 0),
197 
198  // @Param: PRIMARY
199  // @DisplayName: Choose primary compass
200  // @Description: If more than one compass is available, this selects which compass is the primary. When external compasses are connected, they will be ordered first. NOTE: If no external compass is attached, this parameter is ignored.
201  // @Values: 0:FirstCompass,1:SecondCompass,2:ThirdCompass
202  // @User: Advanced
203  AP_GROUPINFO("PRIMARY", 12, Compass, _primary, 0),
204 
205  // @Param: OFS3_X
206  // @DisplayName: Compass3 offsets in milligauss on the X axis
207  // @Description: Offset to be added to compass3's x-axis values to compensate for metal in the frame
208  // @Range: -400 400
209  // @Units: mGauss
210  // @Increment: 1
211  // @User: Advanced
212 
213  // @Param: OFS3_Y
214  // @DisplayName: Compass3 offsets in milligauss on the Y axis
215  // @Description: Offset to be added to compass3's y-axis values to compensate for metal in the frame
216  // @Range: -400 400
217  // @Units: mGauss
218  // @Increment: 1
219  // @User: Advanced
220 
221  // @Param: OFS3_Z
222  // @DisplayName: Compass3 offsets in milligauss on the Z axis
223  // @Description: Offset to be added to compass3's z-axis values to compensate for metal in the frame
224  // @Range: -400 400
225  // @Units: mGauss
226  // @Increment: 1
227  // @User: Advanced
228  AP_GROUPINFO("OFS3", 13, Compass, _state[2].offset, 0),
229 
230  // @Param: MOT3_X
231  // @DisplayName: Motor interference compensation to compass3 for body frame X axis
232  // @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)
233  // @Range: -1000 1000
234  // @Units: mGauss/A
235  // @Increment: 1
236  // @User: Advanced
237 
238  // @Param: MOT3_Y
239  // @DisplayName: Motor interference compensation to compass3 for body frame Y axis
240  // @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)
241  // @Range: -1000 1000
242  // @Units: mGauss/A
243  // @Increment: 1
244  // @User: Advanced
245 
246  // @Param: MOT3_Z
247  // @DisplayName: Motor interference compensation to compass3 for body frame Z axis
248  // @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)
249  // @Range: -1000 1000
250  // @Units: mGauss/A
251  // @Increment: 1
252  // @User: Advanced
253  AP_GROUPINFO("MOT3", 14, Compass, _state[2].motor_compensation, 0),
254 
255  // @Param: DEV_ID
256  // @DisplayName: Compass device id
257  // @Description: Compass device id. Automatically detected, do not set manually
258  // @User: Advanced
259  AP_GROUPINFO("DEV_ID", 15, Compass, _state[0].dev_id, 0),
260 
261  // @Param: DEV_ID2
262  // @DisplayName: Compass2 device id
263  // @Description: Second compass's device id. Automatically detected, do not set manually
264  // @User: Advanced
265  AP_GROUPINFO("DEV_ID2", 16, Compass, _state[1].dev_id, 0),
266 
267  // @Param: DEV_ID3
268  // @DisplayName: Compass3 device id
269  // @Description: Third compass's device id. Automatically detected, do not set manually
270  // @User: Advanced
271  AP_GROUPINFO("DEV_ID3", 17, Compass, _state[2].dev_id, 0),
272 
273  // @Param: USE2
274  // @DisplayName: Compass2 used for yaw
275  // @Description: Enable or disable the second compass for determining heading.
276  // @Values: 0:Disabled,1:Enabled
277  // @User: Advanced
278  AP_GROUPINFO("USE2", 18, Compass, _state[1].use_for_yaw, 1),
279 
280  // @Param: ORIENT2
281  // @DisplayName: Compass2 orientation
282  // @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.
283  // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw135,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315
284  // @User: Advanced
285  AP_GROUPINFO("ORIENT2", 19, Compass, _state[1].orientation, ROTATION_NONE),
286 
287  // @Param: EXTERN2
288  // @DisplayName: Compass2 is attached via an external cable
289  // @Description: Configure second compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. 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.
290  // @Values: 0:Internal,1:External,2:ForcedExternal
291  // @User: Advanced
292  AP_GROUPINFO("EXTERN2",20, Compass, _state[1].external, 0),
293 
294  // @Param: USE3
295  // @DisplayName: Compass3 used for yaw
296  // @Description: Enable or disable the third compass for determining heading.
297  // @Values: 0:Disabled,1:Enabled
298  // @User: Advanced
299  AP_GROUPINFO("USE3", 21, Compass, _state[2].use_for_yaw, 1),
300 
301  // @Param: ORIENT3
302  // @DisplayName: Compass3 orientation
303  // @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.
304  // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw135,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315
305  // @User: Advanced
306  AP_GROUPINFO("ORIENT3", 22, Compass, _state[2].orientation, ROTATION_NONE),
307 
308  // @Param: EXTERN3
309  // @DisplayName: Compass3 is attached via an external cable
310  // @Description: Configure third compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. 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.
311  // @Values: 0:Internal,1:External,2:ForcedExternal
312  // @User: Advanced
313  AP_GROUPINFO("EXTERN3",23, Compass, _state[2].external, 0),
314 
315  // @Param: DIA_X
316  // @DisplayName: Compass soft-iron diagonal X component
317  // @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]]
318  // @User: Advanced
319 
320  // @Param: DIA_Y
321  // @DisplayName: Compass soft-iron diagonal Y component
322  // @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]]
323  // @User: Advanced
324 
325  // @Param: DIA_Z
326  // @DisplayName: Compass soft-iron diagonal Z component
327  // @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]]
328  // @User: Advanced
329  AP_GROUPINFO("DIA", 24, Compass, _state[0].diagonals, 0),
330 
331  // @Param: ODI_X
332  // @DisplayName: Compass soft-iron off-diagonal X component
333  // @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]]
334  // @User: Advanced
335 
336  // @Param: ODI_Y
337  // @DisplayName: Compass soft-iron off-diagonal Y component
338  // @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]]
339  // @User: Advanced
340 
341  // @Param: ODI_Z
342  // @DisplayName: Compass soft-iron off-diagonal Z component
343  // @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]]
344  // @User: Advanced
345  AP_GROUPINFO("ODI", 25, Compass, _state[0].offdiagonals, 0),
346 
347  // @Param: DIA2_X
348  // @DisplayName: Compass2 soft-iron diagonal X component
349  // @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]]
350  // @User: Advanced
351 
352  // @Param: DIA2_Y
353  // @DisplayName: Compass2 soft-iron diagonal Y component
354  // @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]]
355  // @User: Advanced
356 
357  // @Param: DIA2_Z
358  // @DisplayName: Compass2 soft-iron diagonal Z component
359  // @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]]
360  // @User: Advanced
361  AP_GROUPINFO("DIA2", 26, Compass, _state[1].diagonals, 0),
362 
363  // @Param: ODI2_X
364  // @DisplayName: Compass2 soft-iron off-diagonal X component
365  // @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]]
366  // @User: Advanced
367 
368  // @Param: ODI2_Y
369  // @DisplayName: Compass2 soft-iron off-diagonal Y component
370  // @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]]
371  // @User: Advanced
372 
373  // @Param: ODI2_Z
374  // @DisplayName: Compass2 soft-iron off-diagonal Z component
375  // @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]]
376  // @User: Advanced
377  AP_GROUPINFO("ODI2", 27, Compass, _state[1].offdiagonals, 0),
378 
379  // @Param: DIA3_X
380  // @DisplayName: Compass3 soft-iron diagonal X component
381  // @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]]
382  // @User: Advanced
383 
384  // @Param: DIA3_Y
385  // @DisplayName: Compass3 soft-iron diagonal Y component
386  // @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]]
387  // @User: Advanced
388 
389  // @Param: DIA3_Z
390  // @DisplayName: Compass3 soft-iron diagonal Z component
391  // @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]]
392  // @User: Advanced
393  AP_GROUPINFO("DIA3", 28, Compass, _state[2].diagonals, 0),
394 
395  // @Param: ODI3_X
396  // @DisplayName: Compass3 soft-iron off-diagonal X component
397  // @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]]
398  // @User: Advanced
399 
400  // @Param: ODI3_Y
401  // @DisplayName: Compass3 soft-iron off-diagonal Y component
402  // @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]]
403  // @User: Advanced
404 
405  // @Param: ODI3_Z
406  // @DisplayName: Compass3 soft-iron off-diagonal Z component
407  // @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]]
408  // @User: Advanced
409  AP_GROUPINFO("ODI3", 29, Compass, _state[2].offdiagonals, 0),
410 
411  // @Param: CAL_FIT
412  // @DisplayName: Compass calibration fitness
413  // @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.
414  // @Range: 4 32
415  // @Values: 4:Very Strict,8:Strict,16:Default,32:Relaxed
416  // @Increment: 0.1
417  // @User: Advanced
418  AP_GROUPINFO("CAL_FIT", 30, Compass, _calibration_threshold, AP_COMPASS_CALIBRATION_FITNESS_DEFAULT),
419 
420  // @Param: OFFS_MAX
421  // @DisplayName: Compass maximum offset
422  // @Description: This sets the maximum allowed compass offset in calibration and arming checks
423  // @Range: 500 3000
424  // @Increment: 1
425  // @User: Advanced
426  AP_GROUPINFO("OFFS_MAX", 31, Compass, _offset_max, AP_COMPASS_OFFSETS_MAX_DEFAULT),
427 
428  // @Group: PMOT
429  // @Path: Compass_PerMotor.cpp
430  AP_SUBGROUPINFO(_per_motor, "PMOT", 32, Compass, Compass_PerMotor),
431 
432  // @Param: TYPEMASK
433  // @DisplayName: Compass disable driver type mask
434  // @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
435  // @Bitmask: 0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,11:UAVCAN,12:QMC5883
436  // @User: Advanced
437  AP_GROUPINFO("TYPEMASK", 33, Compass, _driver_type_mask, 0),
438 
439  // @Param: FLTR_RNG
440  // @DisplayName: Range in which sample is accepted
441  // @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.
442  // @Units: %
443  // @Range: 0 100
444  // @Increment: 1
445  AP_GROUPINFO("FLTR_RNG", 34, Compass, _filter_range, HAL_COMPASS_FILTER_DEFAULT),
446 
448 };
449 
450 // Default constructor.
451 // Note that the Vector/Matrix constructors already implicitly zero
452 // their values.
453 //
455  _compass_cal_autoreboot(false),
456  _cal_complete_requires_reboot(false),
457  _cal_has_run(false),
458  _backend_count(0),
459  _compass_count(0),
460  _board_orientation(ROTATION_NONE),
461  _custom_rotation(nullptr),
462  _null_init_done(false),
463  _hil_mode(false)
464 {
465  if (_singleton != nullptr) {
466 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
467  AP_HAL::panic("Compass must be singleton");
468 #endif
469  return;
470  }
471  _singleton = this;
473  for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {
474  _backends[i] = nullptr;
475  _state[i].last_update_usec = 0;
476  }
477 
478  // default device ids to zero. init() method will overwrite with the actual device ids
479  for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
480  _state[i].dev_id = 0;
481  }
482 }
483 
484 // Default init method
485 //
486 bool
488 {
489  if (_compass_count == 0) {
490  // detect available backends. Only called once
492  }
493  if (_compass_count != 0) {
494  // get initial health status
495  hal.scheduler->delay(100);
496  read();
497  }
498  return true;
499 }
500 
501 // Register a new compass instance
502 //
504 {
506  AP_HAL::panic("Too many compass instances");
507  }
508  return _compass_count++;
509 }
510 
511 bool Compass::_add_backend(AP_Compass_Backend *backend, const char *name, bool external)
512 {
513  if (!backend) {
514  return false;
515  }
516 
518  AP_HAL::panic("Too many compass backends");
519  }
520 
521  _backends[_backend_count++] = backend;
522 
523  return true;
524 }
525 
526 /*
527  return true if a driver type is enabled
528  */
529 bool Compass::_driver_enabled(enum DriverType driver_type)
530 {
531  uint32_t mask = (1U<<uint8_t(driver_type));
532  return (mask & uint32_t(_driver_type_mask.get())) == 0;
533 }
534 
535 /*
536  see if we already have probed a driver by bus type
537  */
538 bool Compass::_have_driver(AP_HAL::Device::BusType bus_type, uint8_t bus_num, uint8_t address, uint8_t devtype) const
539 {
540  uint32_t id = AP_HAL::Device::make_bus_id(bus_type, bus_num, address, devtype);
541  for (uint8_t i=0; i<_compass_count; i++) {
542  if (id == uint32_t(_state[i].dev_id.get())) {
543  return true;
544  }
545  }
546  return false;
547 }
548 
549 /*
550  detect available backends for this board
551  */
553 {
554  if (_hil_mode) {
555  _add_backend(AP_Compass_HIL::detect(*this), nullptr, false);
556  return;
557  }
558 
559 #if AP_FEATURE_BOARD_DETECT
561  // default to disabling LIS3MDL on pixhawk2 due to hardware issue
562  _driver_type_mask.set_default(1U<<DRIVER_LIS3MDL);
563  }
564 #endif
565 
566 /*
567  macro to add a backend with check for too many backends or compass
568  instances. We don't try to start more than the maximum allowed
569  */
570 #define ADD_BACKEND(driver_type, backend, name, external) \
571  do { if (_driver_enabled(driver_type)) { _add_backend(backend, name, external); } \
572  if (_backend_count == COMPASS_MAX_BACKEND || \
573  _compass_count == COMPASS_MAX_INSTANCES) { \
574  return; \
575  } \
576  } while (0)
577 
578 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
579  ADD_BACKEND(DRIVER_SITL, new AP_Compass_SITL(*this), nullptr, false);
580  return;
581 #endif
582 
583 #if HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL
584  ADD_BACKEND(DRIVER_SITL, AP_Compass_HIL::detect(*this), nullptr, false);
585 #elif AP_FEATURE_BOARD_DETECT
586  switch (AP_BoardConfig::get_board_type()) {
597  // external i2c bus
599  true, ROTATION_ROLL_180),
601 
603  // internal i2c bus
605  both_i2c_external, both_i2c_external?ROTATION_ROLL_180:ROTATION_YAW_270),
606  AP_Compass_HMC5843::name, both_i2c_external);
607  }
608 
609  //external i2c bus
611  true,ROTATION_ROLL_180),
613  //internal i2c bus
615  both_i2c_external, both_i2c_external?ROTATION_ROLL_180:ROTATION_ROLL_180_YAW_270),
616  AP_Compass_QMC5883L::name,both_i2c_external);
617 
618 #if !HAL_MINIMIZE_FEATURES
619  // AK09916 on ICM20948
625 
629  both_i2c_external, ROTATION_PITCH_180_YAW_90),
631 
632  // lis3mdl on bus 0 with default address
634  both_i2c_external, both_i2c_external?ROTATION_YAW_90:ROTATION_NONE),
635  AP_Compass_LIS3MDL::name, both_i2c_external);
636 
637  // lis3mdl on bus 0 with alternate address
639  both_i2c_external, both_i2c_external?ROTATION_YAW_90:ROTATION_NONE),
640  AP_Compass_LIS3MDL::name, both_i2c_external);
641 
642  // external lis3mdl on bus 1 with default address
644  true, ROTATION_YAW_90),
646 
647  // external lis3mdl on bus 1 with alternate address
649  true, ROTATION_YAW_90),
651 
652  // AK09916. This can be found twice, due to the ICM20948 i2c bus pass-thru, so we need to be careful to avoid that
655  true, ROTATION_YAW_270),
657  }
660  both_i2c_external, both_i2c_external?ROTATION_YAW_270:ROTATION_NONE),
661  AP_Compass_AK09916::name, both_i2c_external);
662  }
663 
664  // IST8310 on external and internal bus
667 
669  both_i2c_external, ROTATION_PITCH_180), AP_Compass_IST8310::name, both_i2c_external);
670 #endif // HAL_MINIMIZE_FEATURES
671  }
672  break;
673 
676  AP_Compass_BMM150::probe(*this, hal.i2c_mgr->get_device(0, 0x10)),
678  break;
679 
681 #ifdef HAL_COMPASS_IST8310_I2C_BUS
684 #endif
685  break;
686 
688  // external i2c bus
690  true, ROTATION_ROLL_180),
692  }
693  // internal i2c bus
695  false, ROTATION_YAW_270),
696  AP_Compass_HMC5843::name, false);
697  break;
698 
705  // external i2c bus
707  true, ROTATION_ROLL_180),
709  }
710  break;
711 
712  default:
713  break;
714  }
715  switch (AP_BoardConfig::get_board_type()) {
718  false, ROTATION_PITCH_180),
719  AP_Compass_HMC5843::name, false);
721  AP_Compass_LSM303D::name, false);
722  break;
723 
726  AP_Compass_LSM303D::name, false);
727  // we run the AK8963 only on the 2nd MPU9250, which leaves the
728  // first MPU9250 to run without disturbance at high rate
730  AP_Compass_AK8963::name, false);
731  break;
732 
735  AP_Compass_AK8963::name, false);
736  break;
737 
740  false, ROTATION_PITCH_180),
741  AP_Compass_HMC5843::name, false);
742  // R15 has LIS3MDL on spi bus instead of HMC; same CS pin
744  false, ROTATION_NONE),
745  AP_Compass_LIS3MDL::name, false);
747  AP_Compass_AK8963::name, false);
748  break;
749 
752  AP_Compass_AK8963::name, false);
754  false, ROTATION_NONE),
755  AP_Compass_LIS3MDL::name, false);
756  break;
757 
760  AP_Compass_AK8963::name, false);
761  break;
762 
765  AP_Compass_AK8963::name, false);
766  break;
767 
770  AP_Compass_AK8963::name, false);
771  break;
772 
775  false, ROTATION_YAW_90),
776  AP_Compass_HMC5843::name, false);
778  AP_Compass_LSM303D::name, false);
779  break;
780 
781  default:
782  break;
783  }
784 
785 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BH
787  AP_Compass_HMC5843::name, false);
789 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BBBMINI
793  AP_Compass_AK8963::name, false);
796 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
798  AP_Compass_HMC5843::name, false);
801  { /* UEFI with lpss set to ACPI */
802  "platform/80860F41:05",
803  /* UEFI with lpss set to PCI */
804  "pci0000:00/0000:00:18.6" },
806  true),
808 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO2
810  AP_Compass_LSM9DS1::name, false);
812  AP_Compass_AK8963::name, false);
815 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NAVIO
817  AP_Compass_AK8963::name, false);
820 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_OCPOC_ZYNQ
824  AP_Compass_AK8963::name, false);
825 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_EDGE
828 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
829  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
830  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
832  AP_Compass_AK8963::name, false);
835 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
836  ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, hal.i2c_mgr->get_device(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
837  AP_Compass_AK8963::name, false);
840 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
842  AP_Compass_AK8963::name, false);
845 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250
847  AP_Compass_AK8963::name, false);
848 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
849 #ifndef HAL_COMPASS_HMC5843_ROTATION
850 # define HAL_COMPASS_HMC5843_ROTATION ROTATION_NONE
851 #endif
854  AP_Compass_HMC5843::name, false);
855  #if defined(HAL_COMPASS_HMC5843_I2C_EXT_BUS) && CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
858  #endif
859 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843_MPU6000
861  AP_Compass_HMC5843::name, false);
862 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C
863  ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
864  AP_Compass_AK8963::name, false);
865 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_MPU9250_I2C
866  ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(*this, hal.i2c_mgr->get_device(HAL_COMPASS_AK8963_I2C_BUS, HAL_COMPASS_AK8963_I2C_ADDR)),
867  AP_Compass_AK8963::name, false);
868 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AERO
869  ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_BMM150_I2C_BUS, HAL_COMPASS_BMM150_I2C_ADDR)),
870  AP_Compass_BMM150::name, false);
875 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_LIS3MDL
877  AP_Compass_LIS3MDL::name, false);
878 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_MAG3110
881 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_IST8310
884 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_QMC5883L
886  true,ROTATION_ROLL_180),
891 #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
893  AP_Compass_HMC5843::name, false);
895  AP_Compass_AK8963::name, false);
897  AP_Compass_LSM9DS1::name, false);
898 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_BMM150_I2C
899  ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(*this, hal.i2c_mgr->get_device(HAL_COMPASS_BMM150_I2C_BUS, HAL_COMPASS_BMM150_I2C_ADDR)),
901 #elif HAL_COMPASS_DEFAULT == HAL_COMPASS_NONE
902  // no compass
903 #else
904  #error Unrecognised HAL_COMPASS_TYPE setting
905 #endif
906 
907 
908 #if defined(BOARD_I2C_BUS_EXT) && CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
909 // autodetect external i2c bus
911  true,ROTATION_NONE),
913 
916 
917 
918  // lis3mdl
920  true, ROTATION_NONE),
922 
923  // AK09916
925  true, ROTATION_NONE),
927 
929  ROTATION_NONE),
931 
932  #ifdef HAL_COMPASS_BMM150_I2C_ADDR
933  ADD_BACKEND(DRIVER_BMM150, AP_Compass_BMM150::probe(*this, hal.i2c_mgr->get_device(BOARD_I2C_BUS_EXT, HAL_COMPASS_BMM150_I2C_ADDR)),
935  #endif
936 
939 
942 #endif
943 
944 /* for chibios external board coniguration */
945 #ifdef HAL_EXT_COMPASS_HMC5843_I2C_BUS
947  true, ROTATION_ROLL_180),
949 #endif
950 
951 #if HAL_WITH_UAVCAN
953  bool added;
954  do {
955  added = _add_backend(AP_Compass_UAVCAN::probe(*this), "UAVCAN", true);
957  return;
958  }
959  } while (added);
960  }
961 #endif
962 
963  if (_backend_count == 0 ||
964  _compass_count == 0) {
965  hal.console->printf("No Compass backends available\n");
966  }
967 }
968 
969 void
971 {
972  for (uint8_t i=0; i< _backend_count; i++) {
973  // call accumulate on each of the backend
974  _backends[i]->accumulate();
975  }
976 }
977 
978 bool
980 {
981  for (uint8_t i=0; i< _backend_count; i++) {
982  // call read on each of the backend. This call updates field[i]
983  _backends[i]->read();
984  }
985  uint32_t time = AP_HAL::millis();
986  for (uint8_t i=0; i < COMPASS_MAX_INSTANCES; i++) {
987  _state[i].healthy = (time - _state[i].last_update_ms < 500);
988  }
989  return healthy();
990 }
991 
992 uint8_t
994 {
995  uint8_t healthy_mask = 0;
996  for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
997  if(healthy(i)) {
998  healthy_mask |= 1 << i;
999  }
1000  }
1001  return healthy_mask;
1002 }
1003 
1004 void
1005 Compass::set_offsets(uint8_t i, const Vector3f &offsets)
1006 {
1007  // sanity check compass instance provided
1008  if (i < COMPASS_MAX_INSTANCES) {
1009  _state[i].offset.set(offsets);
1010  }
1011 }
1012 
1013 void
1014 Compass::set_and_save_offsets(uint8_t i, const Vector3f &offsets)
1015 {
1016  // sanity check compass instance provided
1017  if (i < COMPASS_MAX_INSTANCES) {
1018  _state[i].offset.set(offsets);
1019  save_offsets(i);
1020  }
1021 }
1022 
1023 void
1024 Compass::set_and_save_diagonals(uint8_t i, const Vector3f &diagonals)
1025 {
1026  // sanity check compass instance provided
1027  if (i < COMPASS_MAX_INSTANCES) {
1028  _state[i].diagonals.set_and_save(diagonals);
1029  }
1030 }
1031 
1032 void
1033 Compass::set_and_save_offdiagonals(uint8_t i, const Vector3f &offdiagonals)
1034 {
1035  // sanity check compass instance provided
1036  if (i < COMPASS_MAX_INSTANCES) {
1037  _state[i].offdiagonals.set_and_save(offdiagonals);
1038  }
1039 }
1040 
1041 void
1043 {
1044  _state[i].offset.save(); // save offsets
1045  _state[i].dev_id.save(); // save device id corresponding to these offsets
1046 }
1047 
1048 void
1050 {
1051  for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
1052  save_offsets(i);
1053  }
1054 }
1055 
1056 void
1057 Compass::set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor)
1058 {
1059  _state[i].motor_compensation.set(motor_comp_factor);
1060 }
1061 
1062 void
1064 {
1065  _motor_comp_type.save();
1066  for (uint8_t k=0; k<COMPASS_MAX_INSTANCES; k++) {
1067  _state[k].motor_compensation.save();
1068  }
1069 }
1070 
1071 void
1072 Compass::set_initial_location(int32_t latitude, int32_t longitude)
1073 {
1074  // if automatic declination is configured, then compute
1075  // the declination based on the initial GPS fix
1076  if (_auto_declination) {
1077  // Set the declination based on the lat/lng from GPS
1078  _declination.set(radians(
1080  (float)latitude / 10000000,
1081  (float)longitude / 10000000)));
1082  }
1083 }
1084 
1086 bool
1088 {
1089  uint8_t prim = get_primary();
1090  return healthy(prim) && use_for_yaw(prim);
1091 }
1092 
1094 bool
1095 Compass::use_for_yaw(uint8_t i) const
1096 {
1097  // when we are doing in-flight compass learning the state
1098  // estimator must not use the compass. The learning code turns off
1099  // inflight learning when it has converged
1100  return _state[i].use_for_yaw && _learn.get() != LEARN_INFLIGHT;
1101 }
1102 
1103 void
1104 Compass::set_declination(float radians, bool save_to_eeprom)
1105 {
1106  if (save_to_eeprom) {
1107  _declination.set_and_save(radians);
1108  }else{
1109  _declination.set(radians);
1110  }
1111 }
1112 
1113 float
1115 {
1116  return _declination.get();
1117 }
1118 
1119 /*
1120  calculate a compass heading given the attitude from DCM and the mag vector
1121  */
1122 float
1123 Compass::calculate_heading(const Matrix3f &dcm_matrix, uint8_t i) const
1124 {
1125  float cos_pitch_sq = 1.0f-(dcm_matrix.c.x*dcm_matrix.c.x);
1126 
1127  // Tilt compensated magnetic field Y component:
1128  const Vector3f &field = get_field(i);
1129 
1130  float headY = field.y * dcm_matrix.c.z - field.z * dcm_matrix.c.y;
1131 
1132  // Tilt compensated magnetic field X component:
1133  float headX = field.x * cos_pitch_sq - dcm_matrix.c.x * (field.y * dcm_matrix.c.y + field.z * dcm_matrix.c.z);
1134 
1135  // magnetic heading
1136  // 6/4/11 - added constrain to keep bad values from ruining DCM Yaw - Jason S.
1137  float heading = constrain_float(atan2f(-headY,headX), -3.15f, 3.15f);
1138 
1139  // Declination correction (if supplied)
1140  if( fabsf(_declination) > 0.0f )
1141  {
1142  heading = heading + _declination;
1143  if (heading > M_PI) // Angle normalization (-180 deg, 180 deg)
1144  heading -= (2.0f * M_PI);
1145  else if (heading < -M_PI)
1146  heading += (2.0f * M_PI);
1147  }
1148 
1149  return heading;
1150 }
1151 
1156 bool Compass::configured(uint8_t i)
1157 {
1158  // exit immediately if instance is beyond the number of compasses we have available
1159  if (i > get_count()) {
1160  return false;
1161  }
1162 
1163  // exit immediately if all offsets are zero
1164  if (is_zero(get_offsets(i).length())) {
1165  return false;
1166  }
1167 
1168  // backup detected dev_id
1169  int32_t dev_id_orig = _state[i].dev_id;
1170 
1171  // load dev_id from eeprom
1172  _state[i].dev_id.load();
1173 
1174  // if different then the device has not been configured
1175  if (_state[i].dev_id != dev_id_orig) {
1176  // restore device id
1177  _state[i].dev_id = dev_id_orig;
1178  // return failure
1179  return false;
1180  }
1181 
1182  // if we got here then it must be configured
1183  return true;
1184 }
1185 
1187 {
1188  bool all_configured = true;
1189  for(uint8_t i=0; i<get_count(); i++) {
1190  all_configured = all_configured && (!use_for_yaw(i) || configured(i));
1191  }
1192  return all_configured;
1193 }
1194 
1195 // Update raw magnetometer values from HIL data
1196 //
1197 void Compass::setHIL(uint8_t instance, float roll, float pitch, float yaw)
1198 {
1199  Matrix3f R;
1200 
1201  // create a rotation matrix for the given attitude
1202  R.from_euler(roll, pitch, yaw);
1203 
1204  if (!is_equal(_hil.last_declination,get_declination())) {
1206  _hil.last_declination = get_declination();
1207  }
1208 
1209  // convert the earth frame magnetic vector to body frame, and
1210  // apply the offsets
1211  _hil.field[instance] = R.mul_transpose(_hil.Bearth);
1212 
1213  // apply default board orientation for this compass type. This is
1214  // a noop on most boards
1215  _hil.field[instance].rotate(MAG_BOARD_ORIENTATION);
1216 
1217  // add user selectable orientation
1218  _hil.field[instance].rotate((enum Rotation)_state[0].orientation.get());
1219 
1220  if (!_state[0].external) {
1221  // and add in AHRS_ORIENTATION setting if not an external compass
1223  _hil.field[instance] = *_custom_rotation * _hil.field[instance];
1224  } else {
1225  _hil.field[instance].rotate(_board_orientation);
1226  }
1227  }
1228  _hil.healthy[instance] = true;
1229 }
1230 
1231 // Update raw magnetometer values from HIL mag vector
1232 //
1233 void Compass::setHIL(uint8_t instance, const Vector3f &mag, uint32_t update_usec)
1234 {
1235  _hil.field[instance] = mag;
1236  _hil.healthy[instance] = true;
1237  _state[instance].last_update_usec = update_usec;
1238 }
1239 
1240 const Vector3f& Compass::getHIL(uint8_t instance) const
1241 {
1242  return _hil.field[instance];
1243 }
1244 
1245 // setup _Bearth
1247 {
1248  // assume a earth field strength of 400
1249  _hil.Bearth(400, 0, 0);
1250 
1251  // rotate _Bearth for inclination and declination. -66 degrees
1252  // is the inclination in Canberra, Australia
1253  Matrix3f R;
1254  R.from_euler(0, ToRad(66), get_declination());
1255  _hil.Bearth = R * _hil.Bearth;
1256 }
1257 
1258 /*
1259  set the type of motor compensation to use
1260  */
1261 void Compass::motor_compensation_type(const uint8_t comp_type)
1262 {
1263  if (_motor_comp_type <= AP_COMPASS_MOT_COMP_CURRENT && _motor_comp_type != (int8_t)comp_type) {
1264  _motor_comp_type = (int8_t)comp_type;
1265  _thr = 0; // set current throttle to zero
1266  for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
1267  set_motor_compensation(i, Vector3f(0,0,0)); // clear out invalid compensation vectors
1268  }
1269  }
1270 }
1271 
1273 {
1274  Vector3f primary_mag_field = get_field();
1275  Vector3f primary_mag_field_norm;
1276 
1277  if (!primary_mag_field.is_zero()) {
1278  primary_mag_field_norm = primary_mag_field.normalized();
1279  } else {
1280  return false;
1281  }
1282 
1283  Vector2f primary_mag_field_xy = Vector2f(primary_mag_field.x,primary_mag_field.y);
1284  Vector2f primary_mag_field_xy_norm;
1285 
1286  if (!primary_mag_field_xy.is_zero()) {
1287  primary_mag_field_xy_norm = primary_mag_field_xy.normalized();
1288  } else {
1289  return false;
1290  }
1291 
1292  for (uint8_t i=0; i<get_count(); i++) {
1293  if (use_for_yaw(i)) {
1294  Vector3f mag_field = get_field(i);
1295  Vector3f mag_field_norm;
1296 
1297  if (!mag_field.is_zero()) {
1298  mag_field_norm = mag_field.normalized();
1299  } else {
1300  return false;
1301  }
1302 
1303  Vector2f mag_field_xy = Vector2f(mag_field.x,mag_field.y);
1304  Vector2f mag_field_xy_norm;
1305 
1306  if (!mag_field_xy.is_zero()) {
1307  mag_field_xy_norm = mag_field_xy.normalized();
1308  } else {
1309  return false;
1310  }
1311 
1312  float xyz_ang_diff = acosf(constrain_float(mag_field_norm * primary_mag_field_norm,-1.0f,1.0f));
1313  float xy_ang_diff = acosf(constrain_float(mag_field_xy_norm*primary_mag_field_xy_norm,-1.0f,1.0f));
1314  float xy_len_diff = (primary_mag_field_xy-mag_field_xy).length();
1315 
1316  // check for gross misalignment on all axes
1317  bool xyz_ang_diff_large = xyz_ang_diff > AP_COMPASS_MAX_XYZ_ANG_DIFF;
1318 
1319  // check for an unacceptable angle difference on the xy plane
1320  bool xy_ang_diff_large = xy_ang_diff > AP_COMPASS_MAX_XY_ANG_DIFF;
1321 
1322  // check for an unacceptable length difference on the xy plane
1323  bool xy_length_diff_large = xy_len_diff > AP_COMPASS_MAX_XY_LENGTH_DIFF;
1324 
1325  // check for inconsistency in the XY plane
1326  if (xyz_ang_diff_large || xy_ang_diff_large || xy_length_diff_large) {
1327  return false;
1328  }
1329  }
1330  }
1331  return true;
1332 }
1333 
1334 
1335 // singleton instance
1337 
1338 namespace AP {
1339 
1341 {
1342  return *Compass::get_singleton();
1343 }
1344 
1345 }
static uint32_t make_bus_id(enum BusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype)
Definition: Device.h:232
uint8_t register_compass(void)
Definition: AP_Compass.cpp:503
AP_Int8 _auto_declination
Definition: AP_Compass.h:408
Compass & compass()
#define HAL_COMPASS_ICM20948_I2C_ADDR
#define HAL_COMPASS_IST8310_I2C_ADDR
Vector2< float > Vector2f
Definition: vector2.h:239
static constexpr const char * name
#define COMPASS_LEARN_DEFAULT
Definition: AP_Compass.cpp:33
AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define AP_COMPASS_MAX_XYZ_ANG_DIFF
Definition: AP_Compass.h:38
bool _have_driver(AP_HAL::Device::BusType bus_type, uint8_t bus_num, uint8_t address, uint8_t devtype) const
Definition: AP_Compass.cpp:538
Vector3< float > Vector3f
Definition: vector3.h:246
#define AP_COMPASS_MOT_COMP_DISABLED
Definition: AP_Compass.h:18
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation=ROTATION_NONE)
static enum px4_board_type get_board_type(void)
float get_declination() const
uint32_t last_update_usec
Definition: AP_Compass.h:452
AP_Int32 _driver_type_mask
Definition: AP_Compass.h:471
static Compass * get_singleton()
Definition: AP_Compass.h:60
Vector3< T > normalized() const
Definition: vector3.h:188
AP_Int8 _learn
Definition: AP_Compass.h:395
static AP_Compass_Backend * detect(Compass &compass)
AP_HAL::UARTDriver * console
Definition: HAL.h:110
bool _driver_enabled(enum DriverType driver_type)
Definition: AP_Compass.cpp:529
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
void set_and_save_offdiagonals(uint8_t i, const Vector3f &diagonals)
static AP_Compass_Backend * probe(Compass &compass)
#define HAL_COMPASS_HMC5843_I2C_ADDR
const Vector3f & get_offsets(void) const
Definition: AP_Compass.h:167
#define ToRad(x)
Definition: AP_Common.h:53
void setHIL(uint8_t instance, float roll, float pitch, float yaw)
#define HAL_INS_LSM9DS0_A_NAME
Definition: chibios.h:59
static constexpr const char * name
float _thr
Definition: AP_Compass.h:421
#define AP_COMPASS_OFFSETS_MAX_DEFAULT
Definition: AP_Compass.cpp:37
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
static constexpr const char * name
#define HAL_COMPASS_LIS3MDL_I2C_ADDR
bool _add_backend(AP_Compass_Backend *backend, const char *name, bool external)
Definition: AP_Compass.cpp:511
bool init()
Definition: AP_Compass.cpp:487
void set_and_save_offsets(uint8_t i, const Vector3f &offsets)
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
void accumulate()
Definition: AP_Compass.cpp:970
bool read()
Definition: AP_Compass.cpp:979
static constexpr const char * name
#define HAL_COMPASS_HMC5843_ROTATION
Definition: board.h:128
#define HAL_COMPASS_HMC5843_I2C_BUS
Definition: board.h:126
AP_Float _declination
Definition: AP_Compass.h:405
void set_offsets(uint8_t i, const Vector3f &offsets)
const char * name
Definition: BusTest.cpp:11
AP_Vector3f diagonals
Definition: AP_Compass.h:428
Rotation
Definition: rotations.h:27
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external, enum Rotation rotation=ROTATION_NONE)
void set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor)
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
uint8_t get_healthy_mask() const
Definition: AP_Compass.cpp:993
void _setup_earth_field()
AP_Vector3f offdiagonals
Definition: AP_Compass.h:429
uint8_t get_primary(void) const
Definition: AP_Compass.h:277
#define AP_COMPASS_MAX_XY_LENGTH_DIFF
Definition: AP_Compass.h:40
float calculate_heading(const Matrix3f &dcm_matrix) const
Definition: AP_Compass.h:87
virtual void delay(uint16_t ms)=0
void set_and_save_diagonals(uint8_t i, const Vector3f &diagonals)
Vector2< T > normalized() const
Definition: vector2.h:146
AP_HAL::OwnPtr< AP_HAL::I2CDevice > get_device(std::vector< const char *> devpaths, uint8_t address) override
Definition: I2CDevice.cpp:286
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
Definition: AP_AHRS.cpp:486
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
T y
Definition: vector3.h:67
static constexpr const char * name
Vector3< T > c
Definition: matrix3.h:48
#define HAL_MAG3110_I2C_ADDR
uint32_t millis()
Definition: system.cpp:157
#define HAL_COMPASS_FILTER_DEFAULT
Definition: AP_Compass.cpp:41
static constexpr const char * name
AP_Vector3f offset
Definition: AP_Compass.h:427
static constexpr const char * name
T z
Definition: vector3.h:67
AP_Compass_Backend * _backends[COMPASS_MAX_BACKEND]
Definition: AP_Compass.h:388
#define AP_COMPASS_MAX_XY_ANG_DIFF
Definition: AP_Compass.h:39
#define AP_COMPASS_CALIBRATION_FITNESS_DEFAULT
Definition: AP_Compass.h:37
#define HAL_INS_LSM9DS0_EXT_A_NAME
Definition: chibios.h:62
Vector3f field[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:302
static AP_Compass_Backend * probe_mpu9250(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
#define HAL_COMPASS_LIS3MDL_I2C_ADDR2
bool healthy(void) const
Definition: AP_Compass.h:159
bool consistent() const
AP_Int8 _motor_comp_type
Definition: AP_Compass.h:418
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
const Vector3f & getHIL(uint8_t instance) const
#define HAL_COMPASS_AK09916_I2C_ADDR
void _detect_backends(void)
Definition: AP_Compass.cpp:552
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation=ROTATION_NONE)
struct Compass::@17 _hil
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation=ROTATION_NONE)
AP_HAL::I2CDeviceManager * i2c_mgr
Definition: HAL.h:106
Vector3< T > mul_transpose(const Vector3< T > &v) const
Definition: matrix3.cpp:165
uint8_t get_count(void) const
Definition: AP_Compass.h:119
#define HAL_COMPASS_QMC5883L_I2C_ADDR
static float get_declination(float latitude_deg, float longitude_deg)
#define HAL_COMPASS_LIS3MDL_NAME
Definition: chibios.h:74
void set_declination(float radians, bool save_to_eeprom=true)
static constexpr const char * name
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
#define COMPASS_MAX_INSTANCES
Definition: AP_Compass.h:46
bool _hil_mode
Definition: AP_Compass.h:466
void motor_compensation_type(const uint8_t comp_type)
Matrix3f * _custom_rotation
Definition: AP_Compass.h:399
virtual void accumulate(void)
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
static constexpr float radians(float deg)
Definition: AP_Math.h:158
static I2CDeviceManager * from(AP_HAL::I2CDeviceManager *i2c_mgr)
Definition: I2CDevice.h:90
const Vector3f & get_field(void) const
Definition: AP_Compass.h:123
bool is_zero(void) const
Definition: vector2.h:105
#define ADD_BACKEND(driver_type, backend, name, external)
static Compass * _singleton
Definition: AP_Compass.h:334
#define HAL_COMPASS_HMC5843_I2C_EXT_BUS
Definition: board.h:144
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Compass.h:295
uint32_t last_update_ms
Definition: AP_Compass.h:451
virtual void read(void)=0
static constexpr const char * name
static constexpr const char * name
uint8_t _compass_count
Definition: AP_Compass.h:392
bool is_zero(void) const
Definition: vector3.h:159
static AP_Compass_Backend * probe_mpu6000(Compass &compass, enum Rotation rotation=ROTATION_NONE)
#define M_PI
Definition: definitions.h:10
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define AP_COMPASS_MOT_COMP_CURRENT
Definition: AP_Compass.h:20
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
void save_offsets(void)
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
uint8_t _backend_count
Definition: AP_Compass.h:389
#define COMPASS_MAX_BACKEND
Definition: AP_Compass.h:47
bool use_for_yaw(void) const
return true if the compass should be used for yaw calculations
bool configured(void)
#define AP_GROUPEND
Definition: AP_Param.h:121
struct Compass::mag_state _state[COMPASS_MAX_INSTANCES]
void set_initial_location(int32_t latitude, int32_t longitude)
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
T x
Definition: vector3.h:67
enum Rotation _board_orientation
Definition: AP_Compass.h:398
AP_Vector3f motor_compensation
Definition: AP_Compass.h:442
#define BOARD_I2C_BUS_EXT
Definition: board.h:107
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
static AP_Compass_Backend * probe_ICM20948(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev_icm, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
void save_motor_compensation()
#define HAL_COMPASS_HMC5843_NAME
Definition: chibios.h:73