APM:Libraries
AP_NavEKF3.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
3 
4 #include "AP_NavEKF3_core.h"
6 #include <GCS_MAVLink/GCS.h>
7 #include <DataFlash/DataFlash.h>
8 #include <new>
9 
10 /*
11  parameter defaults for different types of vehicle. The
12  APM_BUILD_DIRECTORY is taken from the main vehicle directory name
13  where the code is built.
14  */
15 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_Replay)
16 // copter defaults
17 #define VELNE_M_NSE_DEFAULT 0.5f
18 #define VELD_M_NSE_DEFAULT 0.7f
19 #define POSNE_M_NSE_DEFAULT 0.5f
20 #define ALT_M_NSE_DEFAULT 2.0f
21 #define MAG_M_NSE_DEFAULT 0.05f
22 #define GYRO_P_NSE_DEFAULT 1.5E-02f
23 #define ACC_P_NSE_DEFAULT 3.5E-01f
24 #define GBIAS_P_NSE_DEFAULT 1.0E-03f
25 #define ABIAS_P_NSE_DEFAULT 3.0E-03f
26 #define MAGB_P_NSE_DEFAULT 1.0E-04f
27 #define MAGE_P_NSE_DEFAULT 1.0E-03f
28 #define VEL_I_GATE_DEFAULT 500
29 #define POS_I_GATE_DEFAULT 500
30 #define HGT_I_GATE_DEFAULT 500
31 #define MAG_I_GATE_DEFAULT 300
32 #define MAG_CAL_DEFAULT 3
33 #define GLITCH_RADIUS_DEFAULT 25
34 #define FLOW_MEAS_DELAY 10
35 #define FLOW_M_NSE_DEFAULT 0.25f
36 #define FLOW_I_GATE_DEFAULT 300
37 #define CHECK_SCALER_DEFAULT 100
38 
39 #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
40 // rover defaults
41 #define VELNE_M_NSE_DEFAULT 0.5f
42 #define VELD_M_NSE_DEFAULT 0.7f
43 #define POSNE_M_NSE_DEFAULT 0.5f
44 #define ALT_M_NSE_DEFAULT 2.0f
45 #define MAG_M_NSE_DEFAULT 0.05f
46 #define GYRO_P_NSE_DEFAULT 1.5E-02f
47 #define ACC_P_NSE_DEFAULT 3.5E-01f
48 #define GBIAS_P_NSE_DEFAULT 1.0E-03f
49 #define ABIAS_P_NSE_DEFAULT 3.0E-03f
50 #define MAGB_P_NSE_DEFAULT 1.0E-04f
51 #define MAGE_P_NSE_DEFAULT 1.0E-03f
52 #define VEL_I_GATE_DEFAULT 500
53 #define POS_I_GATE_DEFAULT 500
54 #define HGT_I_GATE_DEFAULT 500
55 #define MAG_I_GATE_DEFAULT 300
56 #define MAG_CAL_DEFAULT 2
57 #define GLITCH_RADIUS_DEFAULT 25
58 #define FLOW_MEAS_DELAY 10
59 #define FLOW_M_NSE_DEFAULT 0.25f
60 #define FLOW_I_GATE_DEFAULT 300
61 #define CHECK_SCALER_DEFAULT 100
62 
63 #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
64 // plane defaults
65 #define VELNE_M_NSE_DEFAULT 0.5f
66 #define VELD_M_NSE_DEFAULT 0.7f
67 #define POSNE_M_NSE_DEFAULT 0.5f
68 #define ALT_M_NSE_DEFAULT 3.0f
69 #define MAG_M_NSE_DEFAULT 0.05f
70 #define GYRO_P_NSE_DEFAULT 1.5E-02f
71 #define ACC_P_NSE_DEFAULT 3.5E-01f
72 #define GBIAS_P_NSE_DEFAULT 1.0E-03f
73 #define ABIAS_P_NSE_DEFAULT 3.0E-03f
74 #define MAGB_P_NSE_DEFAULT 1.0E-04f
75 #define MAGE_P_NSE_DEFAULT 1.0E-03f
76 #define VEL_I_GATE_DEFAULT 500
77 #define POS_I_GATE_DEFAULT 500
78 #define HGT_I_GATE_DEFAULT 500
79 #define MAG_I_GATE_DEFAULT 300
80 #define MAG_CAL_DEFAULT 0
81 #define GLITCH_RADIUS_DEFAULT 25
82 #define FLOW_MEAS_DELAY 10
83 #define FLOW_M_NSE_DEFAULT 0.25f
84 #define FLOW_I_GATE_DEFAULT 300
85 #define CHECK_SCALER_DEFAULT 100
86 
87 #else
88 // build type not specified, use copter defaults
89 #define VELNE_M_NSE_DEFAULT 0.5f
90 #define VELD_M_NSE_DEFAULT 0.7f
91 #define POSNE_M_NSE_DEFAULT 0.5f
92 #define ALT_M_NSE_DEFAULT 2.0f
93 #define MAG_M_NSE_DEFAULT 0.05f
94 #define GYRO_P_NSE_DEFAULT 1.5E-02f
95 #define ACC_P_NSE_DEFAULT 3.5E-01f
96 #define GBIAS_P_NSE_DEFAULT 1.0E-03f
97 #define ABIAS_P_NSE_DEFAULT 3.0E-03f
98 #define MAGB_P_NSE_DEFAULT 1.0E-04f
99 #define MAGE_P_NSE_DEFAULT 1.0E-03f
100 #define VEL_I_GATE_DEFAULT 500
101 #define POS_I_GATE_DEFAULT 500
102 #define HGT_I_GATE_DEFAULT 500
103 #define MAG_I_GATE_DEFAULT 300
104 #define MAG_CAL_DEFAULT 3
105 #define GLITCH_RADIUS_DEFAULT 25
106 #define FLOW_MEAS_DELAY 10
107 #define FLOW_M_NSE_DEFAULT 0.25f
108 #define FLOW_I_GATE_DEFAULT 300
109 #define CHECK_SCALER_DEFAULT 100
110 
111 #endif // APM_BUILD_DIRECTORY
112 
113 extern const AP_HAL::HAL& hal;
114 
115 // Define tuning parameters
117 
118  // @Param: ENABLE
119  // @DisplayName: Enable EKF3
120  // @Description: This enables EKF3. Enabling EKF3 only makes the maths run, it does not mean it will be used for flight control. To use it for flight control set AHRS_EKF_TYPE=3. A reboot or restart will need to be performed after changing the value of EK3_ENABLE for it to take effect.
121  // @Values: 0:Disabled, 1:Enabled
122  // @User: Advanced
123  // @RebootRequired: True
124  AP_GROUPINFO_FLAGS("ENABLE", 0, NavEKF3, _enable, 0, AP_PARAM_FLAG_ENABLE),
125 
126  // GPS measurement parameters
127 
128  // @Param: GPS_TYPE
129  // @DisplayName: GPS mode control
130  // @Description: This controls use of GPS measurements : 0 = use 3D velocity & 2D position, 1 = use 2D velocity and 2D position, 2 = use 2D position, 3 = Inhibit GPS use - this can be useful when flying with an optical flow sensor in an environment where GPS quality is poor and subject to large multipath errors.
131  // @Values: 0:GPS 3D Vel and 2D Pos, 1:GPS 2D vel and 2D pos, 2:GPS 2D pos, 3:No GPS
132  // @User: Advanced
133  AP_GROUPINFO("GPS_TYPE", 1, NavEKF3, _fusionModeGPS, 0),
134 
135  // @Param: VELNE_M_NSE
136  // @DisplayName: GPS horizontal velocity measurement noise (m/s)
137  // @Description: This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set horizontal velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS horizontal velocity measurements.
138  // @Range: 0.05 5.0
139  // @Increment: 0.05
140  // @User: Advanced
141  // @Units: m/s
142  AP_GROUPINFO("VELNE_M_NSE", 2, NavEKF3, _gpsHorizVelNoise, VELNE_M_NSE_DEFAULT),
143 
144  // @Param: VELD_M_NSE
145  // @DisplayName: GPS vertical velocity measurement noise (m/s)
146  // @Description: This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set vertical velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS vertical velocity measurements.
147  // @Range: 0.05 5.0
148  // @Increment: 0.05
149  // @User: Advanced
150  // @Units: m/s
151  AP_GROUPINFO("VELD_M_NSE", 3, NavEKF3, _gpsVertVelNoise, VELD_M_NSE_DEFAULT),
152 
153  // @Param: VEL_I_GATE
154  // @DisplayName: GPS velocity innovation gate size
155  // @Description: This sets the percentage number of standard deviations applied to the GPS velocity measurement innovation consistency check. Decreasing it makes it more likely that good measurements willbe rejected. Increasing it makes it more likely that bad measurements will be accepted.
156  // @Range: 100 1000
157  // @Increment: 25
158  // @User: Advanced
159  AP_GROUPINFO("VEL_I_GATE", 4, NavEKF3, _gpsVelInnovGate, VEL_I_GATE_DEFAULT),
160 
161  // @Param: POSNE_M_NSE
162  // @DisplayName: GPS horizontal position measurement noise (m)
163  // @Description: This sets the GPS horizontal position observation noise. Increasing it reduces the weighting of GPS horizontal position measurements.
164  // @Range: 0.1 10.0
165  // @Increment: 0.1
166  // @User: Advanced
167  // @Units: m
168  AP_GROUPINFO("POSNE_M_NSE", 5, NavEKF3, _gpsHorizPosNoise, POSNE_M_NSE_DEFAULT),
169 
170  // @Param: POS_I_GATE
171  // @DisplayName: GPS position measurement gate size
172  // @Description: This sets the percentage number of standard deviations applied to the GPS position measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
173  // @Range: 100 1000
174  // @Increment: 25
175  // @User: Advanced
176  AP_GROUPINFO("POS_I_GATE", 6, NavEKF3, _gpsPosInnovGate, POS_I_GATE_DEFAULT),
177 
178  // @Param: GLITCH_RAD
179  // @DisplayName: GPS glitch radius gate size (m)
180  // @Description: This controls the maximum radial uncertainty in position between the value predicted by the filter and the value measured by the GPS before the filter position and velocity states are reset to the GPS. Making this value larger allows the filter to ignore larger GPS glitches but also means that non-GPS errors such as IMU and compass can create a larger error in position before the filter is forced back to the GPS position.
181  // @Range: 10 100
182  // @Increment: 5
183  // @User: Advanced
184  // @Units: m
185  AP_GROUPINFO("GLITCH_RAD", 7, NavEKF3, _gpsGlitchRadiusMax, GLITCH_RADIUS_DEFAULT),
186 
187  // 8 previously used for EKF3_GPS_DELAY parameter that has been deprecated.
188  // The EKF now takes its GPs delay form the GPS library with the default delays
189  // specified by the GPS_DELAY and GPS_DELAY2 parameters.
190 
191  // Height measurement parameters
192 
193  // @Param: ALT_SOURCE
194  // @DisplayName: Primary altitude sensor source
195  // @Description: This parameter controls the primary height sensor used by the EKF. If the selected option cannot be used, it will default to Baro as the primary height source. Setting 0 will use the baro altitude at all times. Setting 1 uses the range finder and is only available in combination with optical flow navigation (EK3_GPS_TYPE = 3). Setting 2 uses GPS. Setting 3 uses the range beacon data. NOTE - the EK3_RNG_USE_HGT parameter can be used to switch to range-finder when close to the ground.
196  // @Values: 0:Use Baro, 1:Use Range Finder, 2:Use GPS, 3:Use Range Beacon
197  // @User: Advanced
198  // @RebootRequired: True
199  AP_GROUPINFO("ALT_SOURCE", 9, NavEKF3, _altSource, 0),
200 
201  // @Param: ALT_M_NSE
202  // @DisplayName: Altitude measurement noise (m)
203  // @Description: This is the RMS value of noise in the altitude measurement. Increasing it reduces the weighting of the baro measurement and will make the filter respond more slowly to baro measurement errors, but will make it more sensitive to GPS and accelerometer errors.
204  // @Range: 0.1 10.0
205  // @Increment: 0.1
206  // @User: Advanced
207  // @Units: m
208  AP_GROUPINFO("ALT_M_NSE", 10, NavEKF3, _baroAltNoise, ALT_M_NSE_DEFAULT),
209 
210  // @Param: HGT_I_GATE
211  // @DisplayName: Height measurement gate size
212  // @Description: This sets the percentage number of standard deviations applied to the height measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
213  // @Range: 100 1000
214  // @Increment: 25
215  // @User: Advanced
216  AP_GROUPINFO("HGT_I_GATE", 11, NavEKF3, _hgtInnovGate, HGT_I_GATE_DEFAULT),
217 
218  // @Param: HGT_DELAY
219  // @DisplayName: Height measurement delay (msec)
220  // @Description: This is the number of msec that the Height measurements lag behind the inertial measurements.
221  // @Range: 0 250
222  // @Increment: 10
223  // @RebootRequired: True
224  // @User: Advanced
225  // @Units: ms
226  // @RebootRequired: True
227  AP_GROUPINFO("HGT_DELAY", 12, NavEKF3, _hgtDelay_ms, 60),
228 
229  // Magnetometer measurement parameters
230 
231  // @Param: MAG_M_NSE
232  // @DisplayName: Magnetometer measurement noise (Gauss)
233  // @Description: This is the RMS value of noise in magnetometer measurements. Increasing it reduces the weighting on these measurements.
234  // @Range: 0.01 0.5
235  // @Increment: 0.01
236  // @User: Advanced
237  // @Units: Gauss
238  AP_GROUPINFO("MAG_M_NSE", 13, NavEKF3, _magNoise, MAG_M_NSE_DEFAULT),
239 
240  // @Param: MAG_CAL
241  // @DisplayName: Magnetometer default fusion mode
242  // @Description: This determines when the filter will use the 3-axis magnetometer fusion model that estimates both earth and body fixed magnetic field states and when it will use a simpler magnetic heading fusion model that does not use magnetic field states. The 3-axis magnetometer fusion is only suitable for use when the external magnetic field environment is stable. EK3_MAG_CAL = 0 uses heading fusion on ground, 3-axis fusion in-flight, and is the default setting for Plane users. EK3_MAG_CAL = 1 uses 3-axis fusion only when manoeuvring. EK3_MAG_CAL = 2 uses heading fusion at all times, is recommended if the external magnetic field is varying and is the default for rovers. EK3_MAG_CAL = 3 uses heading fusion on the ground and 3-axis fusion after the first in-air field and yaw reset has completed, and is the default for copters. EK3_MAG_CAL = 4 uses 3-axis fusion at all times. NOTE : Use of simple heading magnetometer fusion makes vehicle compass calibration and alignment errors harder for the EKF to detect which reduces the sensitivity of the Copter EKF failsafe algorithm. NOTE: The fusion mode can be forced to 2 for specific EKF cores using the EK3_MAG_MASK parameter.
243  // @Values: 0:When flying,1:When manoeuvring,2:Never,3:After first climb yaw reset,4:Always
244  // @User: Advanced
245  // @RebootRequired: True
246  AP_GROUPINFO("MAG_CAL", 14, NavEKF3, _magCal, MAG_CAL_DEFAULT),
247 
248  // @Param: MAG_I_GATE
249  // @DisplayName: Magnetometer measurement gate size
250  // @Description: This sets the percentage number of standard deviations applied to the magnetometer measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
251  // @Range: 100 1000
252  // @Increment: 25
253  // @User: Advanced
254  AP_GROUPINFO("MAG_I_GATE", 15, NavEKF3, _magInnovGate, MAG_I_GATE_DEFAULT),
255 
256  // Airspeed measurement parameters
257 
258  // @Param: EAS_M_NSE
259  // @DisplayName: Equivalent airspeed measurement noise (m/s)
260  // @Description: This is the RMS value of noise in equivalent airspeed measurements used by planes. Increasing it reduces the weighting of airspeed measurements and will make wind speed estimates less noisy and slower to converge. Increasing also increases navigation errors when dead-reckoning without GPS measurements.
261  // @Range: 0.5 5.0
262  // @Increment: 0.1
263  // @User: Advanced
264  // @Units: m/s
265  AP_GROUPINFO("EAS_M_NSE", 16, NavEKF3, _easNoise, 1.4f),
266 
267  // @Param: EAS_I_GATE
268  // @DisplayName: Airspeed measurement gate size
269  // @Description: This sets the percentage number of standard deviations applied to the airspeed measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
270  // @Range: 100 1000
271  // @Increment: 25
272  // @User: Advanced
273  AP_GROUPINFO("EAS_I_GATE", 17, NavEKF3, _tasInnovGate, 400),
274 
275  // Rangefinder measurement parameters
276 
277  // @Param: RNG_M_NSE
278  // @DisplayName: Range finder measurement noise (m)
279  // @Description: This is the RMS value of noise in the range finder measurement. Increasing it reduces the weighting on this measurement.
280  // @Range: 0.1 10.0
281  // @Increment: 0.1
282  // @User: Advanced
283  // @Units: m
284  AP_GROUPINFO("RNG_M_NSE", 18, NavEKF3, _rngNoise, 0.5f),
285 
286  // @Param: RNG_I_GATE
287  // @DisplayName: Range finder measurement gate size
288  // @Description: This sets the percentage number of standard deviations applied to the range finder innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
289  // @Range: 100 1000
290  // @Increment: 25
291  // @User: Advanced
292  AP_GROUPINFO("RNG_I_GATE", 19, NavEKF3, _rngInnovGate, 500),
293 
294  // Optical flow measurement parameters
295 
296  // @Param: MAX_FLOW
297  // @DisplayName: Maximum valid optical flow rate
298  // @Description: This sets the magnitude maximum optical flow rate in rad/sec that will be accepted by the filter
299  // @Range: 1.0 4.0
300  // @Increment: 0.1
301  // @User: Advanced
302  // @Units: rad/s
303  AP_GROUPINFO("MAX_FLOW", 20, NavEKF3, _maxFlowRate, 2.5f),
304 
305  // @Param: FLOW_M_NSE
306  // @DisplayName: Optical flow measurement noise (rad/s)
307  // @Description: This is the RMS value of noise and errors in optical flow measurements. Increasing it reduces the weighting on these measurements.
308  // @Range: 0.05 1.0
309  // @Increment: 0.05
310  // @User: Advanced
311  // @Units: rad/s
312  AP_GROUPINFO("FLOW_M_NSE", 21, NavEKF3, _flowNoise, FLOW_M_NSE_DEFAULT),
313 
314  // @Param: FLOW_I_GATE
315  // @DisplayName: Optical Flow measurement gate size
316  // @Description: This sets the percentage number of standard deviations applied to the optical flow innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
317  // @Range: 100 1000
318  // @Increment: 25
319  // @User: Advanced
320  AP_GROUPINFO("FLOW_I_GATE", 22, NavEKF3, _flowInnovGate, FLOW_I_GATE_DEFAULT),
321 
322  // @Param: FLOW_DELAY
323  // @DisplayName: Optical Flow measurement delay (msec)
324  // @Description: This is the number of msec that the optical flow measurements lag behind the inertial measurements. It is the time from the end of the optical flow averaging period and does not include the time delay due to the 100msec of averaging within the flow sensor.
325  // @Range: 0 250
326  // @Increment: 10
327  // @RebootRequired: True
328  // @User: Advanced
329  // @Units: ms
330  // @RebootRequired: True
331  AP_GROUPINFO("FLOW_DELAY", 23, NavEKF3, _flowDelay_ms, FLOW_MEAS_DELAY),
332 
333  // State and Covariance Predition Parameters
334 
335  // @Param: GYRO_P_NSE
336  // @DisplayName: Rate gyro noise (rad/s)
337  // @Description: This control disturbance noise controls the growth of estimated error due to gyro measurement errors excluding bias. Increasing it makes the flter trust the gyro measurements less and other measurements more.
338  // @Range: 0.0001 0.1
339  // @Increment: 0.0001
340  // @User: Advanced
341  // @Units: rad/s
342  AP_GROUPINFO("GYRO_P_NSE", 24, NavEKF3, _gyrNoise, GYRO_P_NSE_DEFAULT),
343 
344  // @Param: ACC_P_NSE
345  // @DisplayName: Accelerometer noise (m/s^2)
346  // @Description: This control disturbance noise controls the growth of estimated error due to accelerometer measurement errors excluding bias. Increasing it makes the flter trust the accelerometer measurements less and other measurements more.
347  // @Range: 0.01 1.0
348  // @Increment: 0.01
349  // @User: Advanced
350  // @Units: m/s/s
351  AP_GROUPINFO("ACC_P_NSE", 25, NavEKF3, _accNoise, ACC_P_NSE_DEFAULT),
352 
353  // @Param: GBIAS_P_NSE
354  // @DisplayName: Rate gyro bias stability (rad/s/s)
355  // @Description: This state process noise controls growth of the gyro delta angle bias state error estimate. Increasing it makes rate gyro bias estimation faster and noisier.
356  // @Range: 0.00001 0.001
357  // @User: Advanced
358  // @Units: rad/s/s
359  AP_GROUPINFO("GBIAS_P_NSE", 26, NavEKF3, _gyroBiasProcessNoise, GBIAS_P_NSE_DEFAULT),
360 
361  // 27 previously used for EK2_GSCL_P_NSE parameter that has been removed
362 
363  // @Param: ABIAS_P_NSE
364  // @DisplayName: Accelerometer bias stability (m/s^3)
365  // @Description: This noise controls the growth of the vertical accelerometer delta velocity bias state error estimate. Increasing it makes accelerometer bias estimation faster and noisier.
366  // @Range: 0.00001 0.001
367  // @User: Advanced
368  // @Units: m/s/s/s
369  AP_GROUPINFO("ABIAS_P_NSE", 28, NavEKF3, _accelBiasProcessNoise, ABIAS_P_NSE_DEFAULT),
370 
371  // 29 previously used for EK2_MAG_P_NSE parameter that has been replaced with EK3_MAGE_P_NSE and EK3_MAGB_P_NSE
372 
373  // @Param: WIND_P_NSE
374  // @DisplayName: Wind velocity process noise (m/s^2)
375  // @Description: This state process noise controls the growth of wind state error estimates. Increasing it makes wind estimation faster and noisier.
376  // @Range: 0.01 1.0
377  // @Increment: 0.1
378  // @User: Advanced
379  // @Units: m/s/s
380  AP_GROUPINFO("WIND_P_NSE", 30, NavEKF3, _windVelProcessNoise, 0.1f),
381 
382  // @Param: WIND_PSCALE
383  // @DisplayName: Height rate to wind process noise scaler
384  // @Description: This controls how much the process noise on the wind states is increased when gaining or losing altitude to take into account changes in wind speed and direction with altitude. Increasing this parameter increases how rapidly the wind states adapt when changing altitude, but does make wind velocity estimation noiser.
385  // @Range: 0.0 1.0
386  // @Increment: 0.1
387  // @User: Advanced
388  AP_GROUPINFO("WIND_PSCALE", 31, NavEKF3, _wndVarHgtRateScale, 0.5f),
389 
390  // @Param: GPS_CHECK
391  // @DisplayName: GPS preflight check
392  // @Description: This is a 1 byte bitmap controlling which GPS preflight checks are performed. Set to 0 to bypass all checks. Set to 255 perform all checks. Set to 3 to check just the number of satellites and HDoP. Set to 31 for the most rigorous checks that will still allow checks to pass when the copter is moving, eg launch from a boat.
393  // @Bitmask: 0:NSats,1:HDoP,2:speed error,3:position error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed
394  // @User: Advanced
395  AP_GROUPINFO("GPS_CHECK", 32, NavEKF3, _gpsCheck, 31),
396 
397  // @Param: IMU_MASK
398  // @DisplayName: Bitmask of active IMUs
399  // @Description: 1 byte bitmap of IMUs to use in EKF3. A separate instance of EKF3 will be started for each IMU selected. Set to 1 to use the first IMU only (default), set to 2 to use the second IMU only, set to 3 to use the first and second IMU. Additional IMU's can be used up to a maximum of 6 if memory and processing resources permit. There may be insufficient memory and processing resources to run multiple instances. If this occurs EKF3 will fail to start.
400  // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU
401  // @User: Advanced
402  // @RebootRequired: True
403  AP_GROUPINFO("IMU_MASK", 33, NavEKF3, _imuMask, 3),
404 
405  // @Param: CHECK_SCALE
406  // @DisplayName: GPS accuracy check scaler (%)
407  // @Description: This scales the thresholds that are used to check GPS accuracy before it is used by the EKF. A value of 100 is the default. Values greater than 100 increase and values less than 100 reduce the maximum GPS error the EKF will accept. A value of 200 will double the allowable GPS error.
408  // @Range: 50 200
409  // @User: Advanced
410  // @Units: %
411  AP_GROUPINFO("CHECK_SCALE", 34, NavEKF3, _gpsCheckScaler, CHECK_SCALER_DEFAULT),
412 
413  // @Param: NOAID_M_NSE
414  // @DisplayName: Non-GPS operation position uncertainty (m)
415  // @Description: This sets the amount of position variation that the EKF allows for when operating without external measurements (eg GPS or optical flow). Increasing this parameter makes the EKF attitude estimate less sensitive to vehicle manoeuvres but more sensitive to IMU errors.
416  // @Range: 0.5 50.0
417  // @User: Advanced
418  // @Units: m
419  AP_GROUPINFO("NOAID_M_NSE", 35, NavEKF3, _noaidHorizNoise, 10.0f),
420 
421  // @Param: LOG_MASK
422  // @DisplayName: EKF sensor logging IMU mask
423  // @Description: This sets the IMU mask of sensors to do full logging for
424  // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU
425  // @User: Advanced
426  // @RebootRequired: True
427  AP_GROUPINFO("LOG_MASK", 36, NavEKF3, _logging_mask, 1),
428 
429  // control of magentic yaw angle fusion
430 
431  // @Param: YAW_M_NSE
432  // @DisplayName: Yaw measurement noise (rad)
433  // @Description: This is the RMS value of noise in yaw measurements from the magnetometer. Increasing it reduces the weighting on these measurements.
434  // @Range: 0.05 1.0
435  // @Increment: 0.05
436  // @User: Advanced
437  // @Units: rad
438  AP_GROUPINFO("YAW_M_NSE", 37, NavEKF3, _yawNoise, 0.5f),
439 
440  // @Param: YAW_I_GATE
441  // @DisplayName: Yaw measurement gate size
442  // @Description: This sets the percentage number of standard deviations applied to the magnetometer yaw measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
443  // @Range: 100 1000
444  // @Increment: 25
445  // @User: Advanced
446  AP_GROUPINFO("YAW_I_GATE", 38, NavEKF3, _yawInnovGate, 300),
447 
448  // @Param: TAU_OUTPUT
449  // @DisplayName: Output complementary filter time constant (centi-sec)
450  // @Description: Sets the time constant of the output complementary filter/predictor in centi-seconds.
451  // @Range: 10 50
452  // @Increment: 5
453  // @User: Advanced
454  // @Units: cs
455  AP_GROUPINFO("TAU_OUTPUT", 39, NavEKF3, _tauVelPosOutput, 25),
456 
457  // @Param: MAGE_P_NSE
458  // @DisplayName: Earth magnetic field process noise (gauss/s)
459  // @Description: This state process noise controls the growth of earth magnetic field state error estimates. Increasing it makes earth magnetic field estimation faster and noisier.
460  // @Range: 0.00001 0.01
461  // @User: Advanced
462  // @Units: Gauss/s
463  AP_GROUPINFO("MAGE_P_NSE", 40, NavEKF3, _magEarthProcessNoise, MAGE_P_NSE_DEFAULT),
464 
465  // @Param: MAGB_P_NSE
466  // @DisplayName: Body magnetic field process noise (gauss/s)
467  // @Description: This state process noise controls the growth of body magnetic field state error estimates. Increasing it makes magnetometer bias error estimation faster and noisier.
468  // @Range: 0.00001 0.01
469  // @User: Advanced
470  // @Units: Gauss/s
471  AP_GROUPINFO("MAGB_P_NSE", 41, NavEKF3, _magBodyProcessNoise, MAGB_P_NSE_DEFAULT),
472 
473  // @Param: RNG_USE_HGT
474  // @DisplayName: Range finder switch height percentage
475  // @Description: The range finder will be used as the primary height source when below a specified percentage of the sensor maximum as set by the RNGFND_MAX_CM parameter. Set to -1 to prevent range finder use.
476  // @Range: -1 70
477  // @Increment: 1
478  // @User: Advanced
479  // @Units: %
480  AP_GROUPINFO("RNG_USE_HGT", 42, NavEKF3, _useRngSwHgt, -1),
481 
482  // @Param: TERR_GRAD
483  // @DisplayName: Maximum terrain gradient
484  // @Description: Specifies the maximum gradient of the terrain below the vehicle when it is using range finder as a height reference
485  // @Range: 0 0.2
486  // @Increment: 0.01
487  // @User: Advanced
488  AP_GROUPINFO("TERR_GRAD", 43, NavEKF3, _terrGradMax, 0.1f),
489 
490  // @Param: BCN_M_NSE
491  // @DisplayName: Range beacon measurement noise (m)
492  // @Description: This is the RMS value of noise in the range beacon measurement. Increasing it reduces the weighting on this measurement.
493  // @Range: 0.1 10.0
494  // @Increment: 0.1
495  // @User: Advanced
496  // @Units: m
497  AP_GROUPINFO("BCN_M_NSE", 44, NavEKF3, _rngBcnNoise, 1.0f),
498 
499  // @Param: BCN_I_GTE
500  // @DisplayName: Range beacon measurement gate size
501  // @Description: This sets the percentage number of standard deviations applied to the range beacon measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
502  // @Range: 100 1000
503  // @Increment: 25
504  // @User: Advanced
505  AP_GROUPINFO("BCN_I_GTE", 45, NavEKF3, _rngBcnInnovGate, 500),
506 
507  // @Param: BCN_DELAY
508  // @DisplayName: Range beacon measurement delay (msec)
509  // @Description: This is the number of msec that the range beacon measurements lag behind the inertial measurements.
510  // @Range: 0 250
511  // @Increment: 10
512  // @RebootRequired: True
513  // @User: Advanced
514  // @Units: ms
515  // @RebootRequired: True
516  AP_GROUPINFO("BCN_DELAY", 46, NavEKF3, _rngBcnDelay_ms, 50),
517 
518  // @Param: RNG_USE_SPD
519  // @DisplayName: Range finder max ground speed
520  // @Description: The range finder will not be used as the primary height source when the horizontal ground speed is greater than this value.
521  // @Range: 2.0 6.0
522  // @Increment: 0.5
523  // @User: Advanced
524  // @Units: m/s
525  AP_GROUPINFO("RNG_USE_SPD", 47, NavEKF3, _useRngSwSpd, 2.0f),
526 
527  // @Param: ACC_BIAS_LIM
528  // @DisplayName: Accelerometer bias limit
529  // @Description: The accelerometer bias state will be limited to +- this value
530  // @Range: 0.5 2.5
531  // @Increment: 0.1
532  // @User: Advanced
533  // @Units: m/s/s
534  AP_GROUPINFO("ACC_BIAS_LIM", 48, NavEKF3, _accBiasLim, 1.0f),
535 
536  // @Param: MAG_MASK
537  // @DisplayName: Bitmask of active EKF cores that will always use heading fusion
538  // @Description: 1 byte bitmap of EKF cores that will disable magnetic field states and use simple magnetic heading fusion at all times. This parameter enables specified cores to be used as a backup for flight into an environment with high levels of external magnetic interference which may degrade the EKF attitude estimate when using 3-axis magnetometer fusion. NOTE : Use of a different magnetometer fusion algorithm on different cores makes unwanted EKF core switches due to magnetometer errors more likely.
539  // @Bitmask: 0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF
540  // @User: Advanced
541  // @RebootRequired: True
542  AP_GROUPINFO("MAG_MASK", 49, NavEKF3, _magMask, 0),
543 
544  // @Param: OGN_HGT_MASK
545  // @DisplayName: Bitmask control of EKF reference height correction
546  // @Description: When a height sensor other than GPS is used as the primary height source by the EKF, the position of the zero height datum is defined by that sensor and its frame of reference. If a GPS height measurement is also available, then the height of the WGS-84 height datum used by the EKF can be corrected so that the height returned by the getLLH() function is compensated for primary height sensor drift and change in datum over time. The first two bit positions control when the height datum will be corrected. Correction is performed using a Bayes filter and only operates when GPS quality permits. The third bit position controls where the corrections to the GPS reference datum are applied. Corrections can be applied to the local vertical position or to the reported EKF origin height (default).
547  // @Bitmask: 0:Correct when using Baro height,1:Correct when using range finder height,2:Apply corrections to local position
548  // @User: Advanced
549  // @RebootRequired: True
550  AP_GROUPINFO("OGN_HGT_MASK", 50, NavEKF3, _originHgtMode, 0),
551 
552  // @Param: VIS_VERR_MIN
553  // @DisplayName: Visual odometry minimum velocity error
554  // @Description: This is the 1-STD odometry velocity observation error that will be assumed when maximum quality is reported by the sensor. When quality is between max and min, the error will be calculated using linear interpolation between VIS_VERR_MIN and VIS_VERR_MAX.
555  // @Range: 0.05 0.5
556  // @Increment: 0.05
557  // @User: Advanced
558  // @Units: m/s
559  AP_GROUPINFO("VIS_VERR_MIN", 51, NavEKF3, _visOdmVelErrMin, 0.1f),
560 
561  // @Param: VIS_VERR_MAX
562  // @DisplayName: Visual odometry maximum velocity error
563  // @Description: This is the 1-STD odometry velocity observation error that will be assumed when minimum quality is reported by the sensor. When quality is between max and min, the error will be calculated using linear interpolation between VIS_VERR_MIN and VIS_VERR_MAX.
564  // @Range: 0.5 5.0
565  // @Increment: 0.1
566  // @User: Advanced
567  // @Units: m/s
568  AP_GROUPINFO("VIS_VERR_MAX", 52, NavEKF3, _visOdmVelErrMax, 0.9f),
569 
570  // @Param: WENC_VERR
571  // @DisplayName: Wheel odometry velocity error
572  // @Description: This is the 1-STD odometry velocity observation error that will be assumed when wheel encoder data is being fused.
573  // @Range: 0.01 1.0
574  // @Increment: 0.1
575  // @User: Advanced
576  // @Units: m/s
577  AP_GROUPINFO("WENC_VERR", 53, NavEKF3, _wencOdmVelErr, 0.1f),
578 
580 };
581 
583  _ahrs(ahrs),
584  _rng(rng)
585 {
587 }
588 
589 /*
590  see if we should log some sensor data
591  */
593 {
594  if (!have_ekf_logging()) {
595  return;
596  }
597  if (logging.log_compass) {
599  logging.log_compass = false;
600  }
601  if (logging.log_gps) {
603  logging.log_gps = false;
604  }
605  if (logging.log_baro) {
607  logging.log_baro = false;
608  }
609  if (logging.log_imu) {
611  logging.log_imu = false;
612  }
613 
614  // this is an example of an ad-hoc log in EKF
615  // DataFlash_Class::instance()->Log_Write("NKA", "TimeUS,X", "Qf", AP_HAL::micros64(), (double)2.4f);
616 }
617 
618 
619 // Initialise the filter
621 {
622  if (_enable == 0) {
623  return false;
624  }
625  const AP_InertialSensor &ins = AP::ins();
626 
628 
629  // remember expected frame time
630  _frameTimeUsec = 1e6 / ins.get_sample_rate();
631 
632  // expected number of IMU frames per prediction
633  _framesPerPrediction = uint8_t((EKF_TARGET_DT / (_frameTimeUsec * 1.0e-6) + 0.5));
634 
635  if (core == nullptr) {
636 
637  // see if we will be doing logging
639  if (dataflash != nullptr) {
640  logging.enabled = dataflash->log_replay();
641  }
642 
643  // don't run multiple filters for 1 IMU
644  uint8_t mask = (1U<<ins.get_accel_count())-1;
645  _imuMask.set(_imuMask.get() & mask);
646 
647  // initialise the setup variables
648  for (uint8_t i=0; i<7; i++) {
649  coreSetupRequired[i] = false;
650  coreImuIndex[i] = 0;
651  }
652  num_cores = 0;
653 
654  // count IMUs from mask
655  for (uint8_t i=0; i<7; i++) {
656  if (_imuMask & (1U<<i)) {
658  coreImuIndex[num_cores] = i;
659  num_cores++;
660  }
661  }
662 
663  // check if there is enough memory to create the EKF cores
664  if (hal.util->available_memory() < sizeof(NavEKF3_core)*num_cores + 4096) {
665  gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF3: not enough memory");
666  _enable.set(0);
667  return false;
668  }
669 
670  //try to allocate from CCM RAM, fallback to Normal RAM if not available or full
672  if (core == nullptr) {
673  _enable.set(0);
674  gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF3: allocation failed");
675  return false;
676  }
677  for (uint8_t i = 0; i < num_cores; i++) {
678  //Call Constructors
679  new (&core[i]) NavEKF3_core();
680  }
681  }
682 
683  // Set up any cores that have been created
684  // This specifies the IMU to be used and creates the data buffers
685  // If we are unble to set up a core, return false and try again next time the function is called
686  bool core_setup_success = true;
687  for (uint8_t core_index=0; core_index<num_cores; core_index++) {
688  if (coreSetupRequired[core_index]) {
689  coreSetupRequired[core_index] = !core[core_index].setup_core(this, coreImuIndex[core_index], core_index);
690  if (coreSetupRequired[core_index]) {
691  core_setup_success = false;
692  }
693  }
694  }
695  // exit with failure if any cores could not be setup
696  if (!core_setup_success) {
697  return false;
698  }
699 
700  // Set the primary initially to be the lowest index
701  primary = 0;
702 
703  // initialise the cores. We return success only if all cores
704  // initialise successfully
705  bool ret = true;
706  for (uint8_t i=0; i<num_cores; i++) {
707  ret &= core[i].InitialiseFilterBootstrap();
708  }
709 
710  // zero the structs used capture reset events
711  memset(&yaw_reset_data, 0, sizeof(yaw_reset_data));
712  memset(&pos_reset_data, 0, sizeof(pos_reset_data));
713  memset(&pos_down_reset_data, 0, sizeof(pos_down_reset_data));
714 
715  check_log_write();
716  return ret;
717 }
718 
719 // Update Filter States - this should be called whenever new IMU data is available
721 {
722  if (!core) {
723  return;
724  }
725 
727 
728  const AP_InertialSensor &ins = AP::ins();
729 
730  bool statePredictEnabled[num_cores];
731  for (uint8_t i=0; i<num_cores; i++) {
732  // if we have not overrun by more than 3 IMU frames, and we
733  // have already used more than 1/3 of the CPU budget for this
734  // loop then suppress the prediction step. This allows
735  // multiple EKF instances to cooperate on scheduling
736  if (core[i].getFramesSincePredict() < (_framesPerPrediction+3) &&
738  statePredictEnabled[i] = false;
739  } else {
740  statePredictEnabled[i] = true;
741  }
742  core[i].UpdateFilter(statePredictEnabled[i]);
743  }
744 
745  // If the current core selected has a bad error score or is unhealthy, switch to a healthy core with the lowest fault score
746  // Don't start running the check until the primary core has started returned healthy for at least 10 seconds to avoid switching
747  // due to initial alignment fluctuations and race conditions
748  if (!runCoreSelection) {
749  static uint64_t lastUnhealthyTime_us = 0;
750  if (!core[primary].healthy() || lastUnhealthyTime_us == 0) {
751  lastUnhealthyTime_us = imuSampleTime_us;
752  }
753  runCoreSelection = (imuSampleTime_us - lastUnhealthyTime_us) > 1E7;
754  }
755  float primaryErrorScore = core[primary].errorScore();
756  if ((primaryErrorScore > 1.0f || !core[primary].healthy()) && runCoreSelection) {
757  float lowestErrorScore = 0.67f * primaryErrorScore;
758  uint8_t newPrimaryIndex = primary; // index for new primary
759  for (uint8_t coreIndex=0; coreIndex<num_cores; coreIndex++) {
760 
761  if (coreIndex != primary) {
762  // an alternative core is available for selection only if healthy and if states have been updated on this time step
763  bool altCoreAvailable = core[coreIndex].healthy() && statePredictEnabled[coreIndex];
764 
765  // If the primary core is unhealthy and another core is available, then switch now
766  // If the primary core is still healthy,then switching is optional and will only be done if
767  // a core with a significantly lower error score can be found
768  float altErrorScore = core[coreIndex].errorScore();
769  if (altCoreAvailable && (!core[primary].healthy() || altErrorScore < lowestErrorScore)) {
770  newPrimaryIndex = coreIndex;
771  lowestErrorScore = altErrorScore;
772  }
773  }
774  }
775  // update the yaw and position reset data to capture changes due to the lane switch
776  if (newPrimaryIndex != primary) {
777  updateLaneSwitchYawResetData(newPrimaryIndex, primary);
778  updateLaneSwitchPosResetData(newPrimaryIndex, primary);
779  updateLaneSwitchPosDownResetData(newPrimaryIndex, primary);
780  primary = newPrimaryIndex;
781  }
782  }
783 
784  check_log_write();
785 }
786 
787 // Check basic filter health metrics and return a consolidated health status
788 bool NavEKF3::healthy(void) const
789 {
790  if (!core) {
791  return false;
792  }
793  return core[primary].healthy();
794 }
795 
796 // returns the index of the primary core
797 // return -1 if no primary core selected
799 {
800  if (!core) {
801  return -1;
802  }
803  return primary;
804 }
805 
806 // returns the index of the IMU of the primary core
807 // return -1 if no primary core selected
809 {
810  if (!core) {
811  return -1;
812  }
813  return core[primary].getIMUIndex();
814 }
815 
816 // Write the last calculated NE position relative to the reference point (m).
817 // If a calculated solution is not available, use the best available data and return false
818 // If false returned, do not use for flight control
819 bool NavEKF3::getPosNE(int8_t instance, Vector2f &posNE) const
820 {
821  if (instance < 0 || instance >= num_cores) instance = primary;
822  if (!core) {
823  return false;
824  }
825  return core[instance].getPosNE(posNE);
826 }
827 
828 // Write the last calculated D position relative to the reference point (m).
829 // If a calculated solution is not available, use the best available data and return false
830 // If false returned, do not use for flight control
831 bool NavEKF3::getPosD(int8_t instance, float &posD) const
832 {
833  if (instance < 0 || instance >= num_cores) instance = primary;
834  if (!core) {
835  return false;
836  }
837  return core[instance].getPosD(posD);
838 }
839 
840 // return NED velocity in m/s
841 void NavEKF3::getVelNED(int8_t instance, Vector3f &vel) const
842 {
843  if (instance < 0 || instance >= num_cores) instance = primary;
844  if (core) {
845  core[instance].getVelNED(vel);
846  }
847 }
848 
849 // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s
850 float NavEKF3::getPosDownDerivative(int8_t instance) const
851 {
852  if (instance < 0 || instance >= num_cores) instance = primary;
853  // return the value calculated from a complementary filer applied to the EKF height and vertical acceleration
854  if (core) {
855  return core[instance].getPosDownDerivative();
856  }
857  return 0.0f;
858 }
859 
860 // This returns the specific forces in the NED frame
861 void NavEKF3::getAccelNED(Vector3f &accelNED) const
862 {
863  if (core) {
864  core[primary].getAccelNED(accelNED);
865  }
866 }
867 
868 // return body axis gyro bias estimates in rad/sec
869 void NavEKF3::getGyroBias(int8_t instance, Vector3f &gyroBias) const
870 {
871  if (instance < 0 || instance >= num_cores) instance = primary;
872  if (core) {
873  core[instance].getGyroBias(gyroBias);
874  }
875 }
876 
877 // return accelerometer bias estimate in m/s/s
878 void NavEKF3::getAccelBias(int8_t instance, Vector3f &accelBias) const
879 {
880  if (instance < 0 || instance >= num_cores) instance = primary;
881  if (core) {
882  core[instance].getAccelBias(accelBias);
883  }
884 }
885 
886 // return tilt error convergence metric for the specified instance
887 void NavEKF3::getTiltError(int8_t instance, float &ang) const
888 {
889  if (instance < 0 || instance >= num_cores) instance = primary;
890  if (core) {
891  core[instance].getTiltError(ang);
892  }
893 }
894 
895 // reset body axis gyro bias estimates
897 {
898  if (core) {
899  for (uint8_t i=0; i<num_cores; i++) {
900  core[i].resetGyroBias();
901  }
902  }
903 }
904 
905 // Resets the baro so that it reads zero at the current height
906 // Resets the EKF height to zero
907 // Adjusts the EKf origin height so that the EKF height + origin height is the same as before
908 // Returns true if the height datum reset has been performed
909 // If using a range finder for height no reset is performed and it returns false
911 {
912  bool status = true;
913  if (core) {
914  for (uint8_t i=0; i<num_cores; i++) {
915  if (!core[i].resetHeightDatum()) {
916  status = false;
917  }
918  }
919  } else {
920  status = false;
921  }
922  return status;
923 }
924 
925 // Commands the EKF to not use GPS.
926 // This command must be sent prior to vehicle arming and EKF commencement of GPS usage
927 // Returns 0 if command rejected
928 // Returns 1 if command accepted
930 {
931  if (!core) {
932  return 0;
933  }
934  return core[primary].setInhibitGPS();
935 }
936 
937 // return the horizontal speed limit in m/s set by optical flow sensor limits
938 // return the scale factor to be applied to navigation velocity gains to compensate for increase in velocity noise with height when using optical flow
939 void NavEKF3::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
940 {
941  if (core) {
942  core[primary].getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
943  }
944 }
945 
946 // return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis)
947 void NavEKF3::getWind(int8_t instance, Vector3f &wind) const
948 {
949  if (instance < 0 || instance >= num_cores) instance = primary;
950  if (core) {
951  core[instance].getWind(wind);
952  }
953 }
954 
955 // return earth magnetic field estimates in measurement units / 1000
956 void NavEKF3::getMagNED(int8_t instance, Vector3f &magNED) const
957 {
958  if (instance < 0 || instance >= num_cores) instance = primary;
959  if (core) {
960  core[instance].getMagNED(magNED);
961  }
962 }
963 
964 // return body magnetic field estimates in measurement units / 1000
965 void NavEKF3::getMagXYZ(int8_t instance, Vector3f &magXYZ) const
966 {
967  if (instance < 0 || instance >= num_cores) instance = primary;
968  if (core) {
969  core[instance].getMagXYZ(magXYZ);
970  }
971 }
972 
973 // return the magnetometer in use for the specified instance
974 uint8_t NavEKF3::getActiveMag(int8_t instance) const
975 {
976  if (instance < 0 || instance >= num_cores) instance = primary;
977  if (core) {
978  return core[instance].getActiveMag();
979  } else {
980  return 255;
981  }
982 }
983 
984 // Return estimated magnetometer offsets
985 // Return true if magnetometer offsets are valid
986 bool NavEKF3::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
987 {
988  if (!core) {
989  return false;
990  }
991  // try the primary first, else loop through all of the cores and return when one has offsets for this mag instance
992  if (core[primary].getMagOffsets(mag_idx, magOffsets)) {
993  return true;
994  }
995  for (uint8_t i=0; i<num_cores; i++) {
996  if(core[i].getMagOffsets(mag_idx, magOffsets)) {
997  return true;
998  }
999  }
1000  return false;
1001 }
1002 
1003 // Return the last calculated latitude, longitude and height in WGS-84
1004 // If a calculated location isn't available, return a raw GPS measurement
1005 // The status will return true if a calculation or raw measurement is available
1006 // The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control
1007 bool NavEKF3::getLLH(struct Location &loc) const
1008 {
1009  if (!core) {
1010  return false;
1011  }
1012  return core[primary].getLLH(loc);
1013 }
1014 
1015 // Return the latitude and longitude and height used to set the NED origin for the specified instance
1016 // An out of range instance (eg -1) returns data for the the primary instance
1017 // All NED positions calculated by the filter are relative to this location
1018 // Returns false if the origin has not been set
1019 bool NavEKF3::getOriginLLH(int8_t instance, struct Location &loc) const
1020 {
1021  if (instance < 0 || instance >= num_cores) instance = primary;
1022  if (!core) {
1023  return false;
1024  }
1025  return core[instance].getOriginLLH(loc);
1026 }
1027 
1028 // set the latitude and longitude and height used to set the NED origin
1029 // All NED positions calculated by the filter will be relative to this location
1030 // The origin cannot be set if the filter is in a flight mode (eg vehicle armed)
1031 // Returns false if the filter has rejected the attempt to set the origin
1033 {
1034  if (!core) {
1035  return false;
1036  }
1037  return core[primary].setOriginLLH(loc);
1038 }
1039 
1040 // return estimated height above ground level
1041 // return false if ground height is not being estimated.
1042 bool NavEKF3::getHAGL(float &HAGL) const
1043 {
1044  if (!core) {
1045  return false;
1046  }
1047  return core[primary].getHAGL(HAGL);
1048 }
1049 
1050 // return the Euler roll, pitch and yaw angle in radians for the specified instance
1051 void NavEKF3::getEulerAngles(int8_t instance, Vector3f &eulers) const
1052 {
1053  if (instance < 0 || instance >= num_cores) instance = primary;
1054  if (core) {
1055  core[instance].getEulerAngles(eulers);
1056  }
1057 }
1058 
1059 // return the transformation matrix from XYZ (body) to NED axes
1061 {
1062  if (core) {
1064  }
1065 }
1066 
1067 // return the quaternions defining the rotation from NED to XYZ (body) axes
1068 void NavEKF3::getQuaternion(int8_t instance, Quaternion &quat) const
1069 {
1070  if (instance < 0 || instance >= num_cores) instance = primary;
1071  if (core) {
1072  core[instance].getQuaternion(quat);
1073  }
1074 }
1075 
1076 // return the innovations for the specified instance
1077 void NavEKF3::getInnovations(int8_t instance, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
1078 {
1079  if (instance < 0 || instance >= num_cores) instance = primary;
1080  if (core) {
1081  core[instance].getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov);
1082  }
1083 }
1084 
1085 // publish output observer angular, velocity and position tracking error
1086 void NavEKF3::getOutputTrackingError(int8_t instance, Vector3f &error) const
1087 {
1088  if (instance < 0 || instance >= num_cores) instance = primary;
1089  if (core) {
1090  core[instance].getOutputTrackingError(error);
1091  }
1092 }
1093 
1094 // return the innovation consistency test ratios for the velocity, position, magnetometer and true airspeed measurements
1095 void NavEKF3::getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
1096 {
1097  if (instance < 0 || instance >= num_cores) instance = primary;
1098  if (core) {
1099  core[instance].getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
1100  }
1101 }
1102 
1103 // return the diagonals from the covariance matrix for the specified instance
1104 void NavEKF3::getStateVariances(int8_t instance, float stateVar[24]) const
1105 {
1106  if (instance < 0 || instance >= num_cores) instance = primary;
1107  if (core) {
1108  core[instance].getStateVariances(stateVar);
1109  }
1110 }
1111 
1112 // should we use the compass? This is public so it can be used for
1113 // reporting via ahrs.use_compass()
1114 bool NavEKF3::use_compass(void) const
1115 {
1116  if (!core) {
1117  return false;
1118  }
1119  return core[primary].use_compass();
1120 }
1121 
1122 // write the raw optical flow measurements
1123 // rawFlowQuality is a measured of quality between 0 and 255, with 255 being the best quality
1124 // rawFlowRates are the optical flow rates in rad/sec about the X and Y sensor axes.
1125 // rawGyroRates are the sensor rotation rates in rad/sec measured by the sensors internal gyro
1126 // The sign convention is that a RH physical rotation of the sensor about an axis produces both a positive flow and gyro rate
1127 // msecFlowMeas is the scheduler time in msec when the optical flow data was received from the sensor.
1128 // posOffset is the XYZ flow sensor position in the body frame in m
1129 void NavEKF3::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
1130 {
1131  if (core) {
1132  for (uint8_t i=0; i<num_cores; i++) {
1133  core[i].writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
1134  }
1135  }
1136 }
1137 
1138 // return data for debugging optical flow fusion
1139 void NavEKF3::getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov,
1140  float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
1141 {
1142  if (instance < 0 || instance >= num_cores) instance = primary;
1143  if (core) {
1144  core[instance].getFlowDebug(varFlow, gndOffset, flowInnovX, flowInnovY, auxInnov, HAGL, rngInnov, range, gndOffsetErr);
1145  }
1146 }
1147 
1148 /*
1149  * Write body frame linear and angular displacement measurements from a visual odometry sensor
1150  *
1151  * quality is a normalised confidence value from 0 to 100
1152  * delPos is the XYZ change in linear position measured in body frame and relative to the inertial reference at timeStamp_ms (m)
1153  * delAng is the XYZ angular rotation measured in body frame and relative to the inertial reference at timeStamp_ms (rad)
1154  * delTime is the time interval for the measurement of delPos and delAng (sec)
1155  * timeStamp_ms is the timestamp of the last image used to calculate delPos and delAng (msec)
1156  * posOffset is the XYZ body frame position of the camera focal point (m)
1157 */
1158 void NavEKF3::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
1159 {
1160  if (core) {
1161  for (uint8_t i=0; i<num_cores; i++) {
1162  core[i].writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, posOffset);
1163  }
1164  }
1165 }
1166 
1167 /*
1168  * Write odometry data from a wheel encoder. The axis of rotation is assumed to be parallel to the vehicle body axis
1169  *
1170  * delAng is the measured change in angular position from the previous measurement where a positive rotation is produced by forward motion of the vehicle (rad)
1171  * delTime is the time interval for the measurement of delAng (sec)
1172  * timeStamp_ms is the time when the rotation was last measured (msec)
1173  * posOffset is the XYZ body frame position of the wheel hub (m)
1174 */
1175 void NavEKF3::writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)
1176 {
1177  if (core) {
1178  for (uint8_t i=0; i<num_cores; i++) {
1179  core[i].writeWheelOdom(delAng, delTime, timeStamp_ms, posOffset, radius);
1180  }
1181  }
1182 }
1183 
1184 // return data for debugging body frame odometry fusion
1185 uint32_t NavEKF3::getBodyFrameOdomDebug(int8_t instance, Vector3f &velInnov, Vector3f &velInnovVar) const
1186 {
1187  uint32_t ret = 0;
1188  if (instance < 0 || instance >= num_cores) {
1189  instance = primary;
1190  }
1191 
1192  if (core) {
1193  ret = core[instance].getBodyFrameOdomDebug(velInnov, velInnovVar);
1194  }
1195 
1196  return ret;
1197 }
1198 
1199 // return data for debugging range beacon fusion
1200 bool NavEKF3::getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED,
1201  float &offsetHigh, float &offsetLow, Vector3f &posNED) const
1202 {
1203  if (instance < 0 || instance >= num_cores) instance = primary;
1204  if (core) {
1205  return core[instance].getRangeBeaconDebug(ID, rng, innov, innovVar, testRatio, beaconPosNED, offsetHigh, offsetLow, posNED);
1206  } else {
1207  return false;
1208  }
1209 }
1210 
1211 // called by vehicle code to specify that a takeoff is happening
1212 // causes the EKF to compensate for expected barometer errors due to ground effect
1214 {
1215  if (core) {
1216  for (uint8_t i=0; i<num_cores; i++) {
1217  core[i].setTakeoffExpected(val);
1218  }
1219  }
1220 }
1221 
1222 // called by vehicle code to specify that a touchdown is expected to happen
1223 // causes the EKF to compensate for expected barometer errors due to ground effect
1225 {
1226  if (core) {
1227  for (uint8_t i=0; i<num_cores; i++) {
1228  core[i].setTouchdownExpected(val);
1229  }
1230  }
1231 }
1232 
1233 // Set to true if the terrain underneath is stable enough to be used as a height reference
1234 // in combination with a range finder. Set to false if the terrain underneath the vehicle
1235 // cannot be used as a height reference
1237 {
1238  if (core) {
1239  for (uint8_t i=0; i<num_cores; i++) {
1240  core[i].setTerrainHgtStable(val);
1241  }
1242  }
1243 
1244 }
1245 
1246 /*
1247  return the filter fault status as a bitmasked integer
1248  0 = quaternions are NaN
1249  1 = velocities are NaN
1250  2 = badly conditioned X magnetometer fusion
1251  3 = badly conditioned Y magnetometer fusion
1252  5 = badly conditioned Z magnetometer fusion
1253  6 = badly conditioned airspeed fusion
1254  7 = badly conditioned synthetic sideslip fusion
1255  7 = filter is not initialised
1256 */
1257 void NavEKF3::getFilterFaults(int8_t instance, uint16_t &faults) const
1258 {
1259  if (instance < 0 || instance >= num_cores) instance = primary;
1260  if (core) {
1261  core[instance].getFilterFaults(faults);
1262  } else {
1263  faults = 0;
1264  }
1265 }
1266 
1267 /*
1268  return filter timeout status as a bitmasked integer
1269  0 = position measurement timeout
1270  1 = velocity measurement timeout
1271  2 = height measurement timeout
1272  3 = magnetometer measurement timeout
1273  5 = unassigned
1274  6 = unassigned
1275  7 = unassigned
1276  7 = unassigned
1277 */
1278 void NavEKF3::getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
1279 {
1280  if (instance < 0 || instance >= num_cores) instance = primary;
1281  if (core) {
1282  core[instance].getFilterTimeouts(timeouts);
1283  } else {
1284  timeouts = 0;
1285  }
1286 }
1287 
1288 /*
1289  return filter status flags
1290 */
1291 void NavEKF3::getFilterStatus(int8_t instance, nav_filter_status &status) const
1292 {
1293  if (instance < 0 || instance >= num_cores) instance = primary;
1294  if (core) {
1295  core[instance].getFilterStatus(status);
1296  } else {
1297  memset(&status, 0, sizeof(status));
1298  }
1299 }
1300 
1301 /*
1302 return filter gps quality check status
1303 */
1304 void NavEKF3::getFilterGpsStatus(int8_t instance, nav_gps_status &status) const
1305 {
1306  if (instance < 0 || instance >= num_cores) instance = primary;
1307  if (core) {
1308  core[instance].getFilterGpsStatus(status);
1309  } else {
1310  memset(&status, 0, sizeof(status));
1311  }
1312 }
1313 
1314 // send an EKF_STATUS_REPORT message to GCS
1315 void NavEKF3::send_status_report(mavlink_channel_t chan)
1316 {
1317  if (core) {
1319  }
1320 }
1321 
1322 // provides the height limit to be observed by the control loops
1323 // returns false if no height limiting is required
1324 // this is needed to ensure the vehicle does not fly too high when using optical flow navigation
1325 bool NavEKF3::getHeightControlLimit(float &height) const
1326 {
1327  if (!core) {
1328  return false;
1329  }
1330  return core[primary].getHeightControlLimit(height);
1331 }
1332 
1333 // Returns the amount of yaw angle change (in radians) due to the last yaw angle reset or core selection switch
1334 // Returns the time of the last yaw angle reset or 0 if no reset or core switch has ever occurred
1335 // Where there are multiple consumers, they must access this function on the same frame as each other
1336 uint32_t NavEKF3::getLastYawResetAngle(float &yawAngDelta)
1337 {
1338  if (!core) {
1339  return 0;
1340  }
1341 
1342  yawAngDelta = 0.0f;
1343 
1344  // Do the conversion to msec in one place
1345  uint32_t now_time_ms = imuSampleTime_us / 1000;
1346 
1347  // The last time we switched to the current primary core is the first reset event
1348  uint32_t lastYawReset_ms = yaw_reset_data.last_primary_change;
1349 
1350  // There has been a change notification in the primary core that the controller has not consumed
1351  // or this is a repeated acce
1352  if (yaw_reset_data.core_changed || yaw_reset_data.last_function_call == now_time_ms) {
1353  yawAngDelta = yaw_reset_data.core_delta;
1354  yaw_reset_data.core_changed = false;
1355  }
1356 
1357  // Record last time controller got the yaw reset
1358  yaw_reset_data.last_function_call = now_time_ms;
1359 
1360  // There has been a reset inside the core since we switched so update the time and delta
1361  float temp_yawAng;
1362  uint32_t lastCoreYawReset_ms = core[primary].getLastYawResetAngle(temp_yawAng);
1363  if (lastCoreYawReset_ms > lastYawReset_ms) {
1364  yawAngDelta = wrap_PI(yawAngDelta + temp_yawAng);
1365  lastYawReset_ms = lastCoreYawReset_ms;
1366  }
1367 
1368  return lastYawReset_ms;
1369 }
1370 
1371 // Returns the amount of NE position change due to the last position reset or core switch in metres
1372 // Returns the time of the last reset or 0 if no reset or core switch has ever occurred
1373 // Where there are multiple consumers, they must access this function on the same frame as each other
1375 {
1376  if (!core) {
1377  return 0;
1378  }
1379 
1380  posDelta.zero();
1381 
1382  // Do the conversion to msec in one place
1383  uint32_t now_time_ms = imuSampleTime_us / 1000;
1384 
1385  // The last time we switched to the current primary core is the first reset event
1386  uint32_t lastPosReset_ms = pos_reset_data.last_primary_change;
1387 
1388  // There has been a change in the primary core that the controller has not consumed
1389  // allow for multiple consumers on the same frame
1390  if (pos_reset_data.core_changed || pos_reset_data.last_function_call == now_time_ms) {
1391  posDelta = pos_reset_data.core_delta;
1392  pos_reset_data.core_changed = false;
1393  }
1394 
1395  // Record last time controller got the position reset
1396  pos_reset_data.last_function_call = now_time_ms;
1397 
1398  // There has been a reset inside the core since we switched so update the time and delta
1399  Vector2f tempPosDelta;
1400  uint32_t lastCorePosReset_ms = core[primary].getLastPosNorthEastReset(tempPosDelta);
1401  if (lastCorePosReset_ms > lastPosReset_ms) {
1402  posDelta = posDelta + tempPosDelta;
1403  lastPosReset_ms = lastCorePosReset_ms;
1404  }
1405 
1406  return lastPosReset_ms;
1407 }
1408 
1409 // return the amount of NE velocity change due to the last velocity reset in metres/sec
1410 // returns the time of the last reset or 0 if no reset has ever occurred
1412 {
1413  if (!core) {
1414  return 0;
1415  }
1416  return core[primary].getLastVelNorthEastReset(vel);
1417 }
1418 
1419 // report the reason for why the backend is refusing to initialise
1420 const char *NavEKF3::prearm_failure_reason(void) const
1421 {
1422  if (!core) {
1423  return nullptr;
1424  }
1426 }
1427 
1428 // Returns the amount of vertical position change due to the last reset or core switch in metres
1429 // Returns the time of the last reset or 0 if no reset or core switch has ever occurred
1430 // Where there are multiple consumers, they must access this function on the same frame as each other
1431 uint32_t NavEKF3::getLastPosDownReset(float &posDelta)
1432 {
1433  if (!core) {
1434  return 0;
1435  }
1436 
1437  posDelta = 0.0f;
1438 
1439  // Do the conversion to msec in one place
1440  uint32_t now_time_ms = imuSampleTime_us / 1000;
1441 
1442  // The last time we switched to the current primary core is the first reset event
1443  uint32_t lastPosReset_ms = pos_down_reset_data.last_primary_change;
1444 
1445  // There has been a change in the primary core that the controller has not consumed
1446  // allow for multiple consumers on the same frame
1447  if (pos_down_reset_data.core_changed || pos_down_reset_data.last_function_call == now_time_ms) {
1448  posDelta = pos_down_reset_data.core_delta;
1449  pos_down_reset_data.core_changed = false;
1450  }
1451 
1452  // Record last time controller got the position reset
1453  pos_down_reset_data.last_function_call = now_time_ms;
1454 
1455  // There has been a reset inside the core since we switched so update the time and delta
1456  float tempPosDelta;
1457  uint32_t lastCorePosReset_ms = core[primary].getLastPosDownReset(tempPosDelta);
1458  if (lastCorePosReset_ms > lastPosReset_ms) {
1459  posDelta += tempPosDelta;
1460  lastPosReset_ms = lastCorePosReset_ms;
1461  }
1462 
1463  return lastPosReset_ms;
1464 }
1465 
1466 // update the yaw reset data to capture changes due to a lane switch
1467 void NavEKF3::updateLaneSwitchYawResetData(uint8_t new_primary, uint8_t old_primary)
1468 {
1469  Vector3f eulers_old_primary, eulers_new_primary;
1470  float old_yaw_delta;
1471 
1472  // If core yaw reset data has been consumed reset delta to zero
1473  if (!yaw_reset_data.core_changed) {
1474  yaw_reset_data.core_delta = 0;
1475  }
1476 
1477  // If current primary has reset yaw after controller got it, add it to the delta
1478  if (core[old_primary].getLastYawResetAngle(old_yaw_delta) > yaw_reset_data.last_function_call) {
1479  yaw_reset_data.core_delta += old_yaw_delta;
1480  }
1481 
1482  // Record the yaw delta between current core and new primary core and the timestamp of the core change
1483  // Add current delta in case it hasn't been consumed yet
1484  core[old_primary].getEulerAngles(eulers_old_primary);
1485  core[new_primary].getEulerAngles(eulers_new_primary);
1486  yaw_reset_data.core_delta = wrap_PI(eulers_new_primary.z - eulers_old_primary.z + yaw_reset_data.core_delta);
1487  yaw_reset_data.last_primary_change = imuSampleTime_us / 1000;
1488  yaw_reset_data.core_changed = true;
1489 
1490 }
1491 
1492 // update the position reset data to capture changes due to a lane switch
1493 void NavEKF3::updateLaneSwitchPosResetData(uint8_t new_primary, uint8_t old_primary)
1494 {
1495  Vector2f pos_old_primary, pos_new_primary, old_pos_delta;
1496 
1497  // If core position reset data has been consumed reset delta to zero
1498  if (!pos_reset_data.core_changed) {
1499  pos_reset_data.core_delta.zero();
1500  }
1501 
1502  // If current primary has reset position after controller got it, add it to the delta
1503  if (core[old_primary].getLastPosNorthEastReset(old_pos_delta) > pos_reset_data.last_function_call) {
1504  pos_reset_data.core_delta += old_pos_delta;
1505  }
1506 
1507  // Record the position delta between current core and new primary core and the timestamp of the core change
1508  // Add current delta in case it hasn't been consumed yet
1509  core[old_primary].getPosNE(pos_old_primary);
1510  core[new_primary].getPosNE(pos_new_primary);
1511  pos_reset_data.core_delta = pos_new_primary - pos_old_primary + pos_reset_data.core_delta;
1512  pos_reset_data.last_primary_change = imuSampleTime_us / 1000;
1513  pos_reset_data.core_changed = true;
1514 
1515 }
1516 
1517 // Update the vertical position reset data to capture changes due to a core switch
1518 // This should be called after the decision to switch cores has been made, but before the
1519 // new primary EKF update has been run
1520 void NavEKF3::updateLaneSwitchPosDownResetData(uint8_t new_primary, uint8_t old_primary)
1521 {
1522  float posDownOldPrimary, posDownNewPrimary, oldPosDownDelta;
1523 
1524  // If core position reset data has been consumed reset delta to zero
1525  if (!pos_down_reset_data.core_changed) {
1526  pos_down_reset_data.core_delta = 0.0f;
1527  }
1528 
1529  // If current primary has reset position after controller got it, add it to the delta
1530  if (core[old_primary].getLastPosDownReset(oldPosDownDelta) > pos_down_reset_data.last_function_call) {
1531  pos_down_reset_data.core_delta += oldPosDownDelta;
1532  }
1533 
1534  // Record the position delta between current core and new primary core and the timestamp of the core change
1535  // Add current delta in case it hasn't been consumed yet
1536  core[old_primary].getPosD(posDownOldPrimary);
1537  core[new_primary].getPosD(posDownNewPrimary);
1538  pos_down_reset_data.core_delta = posDownNewPrimary - posDownOldPrimary + pos_down_reset_data.core_delta;
1539  pos_down_reset_data.last_primary_change = imuSampleTime_us / 1000;
1540  pos_down_reset_data.core_changed = true;
1541 
1542 }
1543 
1544 /*
1545  get timing statistics structure
1546 */
1547 void NavEKF3::getTimingStatistics(int8_t instance, struct ekf_timing &timing) const
1548 {
1549  if (instance < 0 || instance >= num_cores) {
1550  instance = primary;
1551  }
1552  if (core) {
1553  core[instance].getTimingStatistics(timing);
1554  } else {
1555  memset(&timing, 0, sizeof(timing));
1556  }
1557 }
1558 
1559 #endif //HAL_CPU_CLASS
void getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
#define GLITCH_RADIUS_DEFAULT
Definition: AP_NavEKF3.cpp:105
virtual uint32_t available_memory(void)
Definition: Util.h:121
#define MAGE_P_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:99
void getRotationBodyToNED(Matrix3f &mat) const
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
#define EKF_TARGET_DT
void getTiltError(int8_t instance, float &ang) const
Definition: AP_NavEKF3.cpp:887
uint32_t get_last_update_usec(void) const
#define ABIAS_P_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:97
float getPosDownDerivative(void) const
bool resetHeightDatum(void)
Definition: AP_NavEKF3.cpp:910
void getFilterFaults(uint16_t &faults) const
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
bool getPosD(float &posD) const
#define VELNE_M_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:89
bool getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow, Vector3f &posNED) const
struct NavEKF3::@148 logging
#define MAG_I_GATE_DEFAULT
Definition: AP_NavEKF3.cpp:103
bool getPosNE(Vector2f &posNE) const
AP_Int8 _logging_mask
Definition: AP_NavEKF3.h:403
void send_status_report(mavlink_channel_t chan)
struct NavEKF3::@151 pos_down_reset_data
bool setup_core(NavEKF3 *_frontend, uint8_t _imu_index, uint8_t _core_index)
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_NavEKF3.h:44
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
void getFilterGpsStatus(int8_t instance, nav_gps_status &faults) const
uint8_t getIMUIndex(void) const
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
bool setOriginLLH(const Location &loc)
uint8_t num_cores
Definition: AP_NavEKF3.h:358
uint32_t getBodyFrameOdomDebug(Vector3f &velInnov, Vector3f &velInnovVar)
uint8_t getActiveMag() const
bool setOriginLLH(const Location &loc)
struct NavEKF3::@150 pos_reset_data
AP_Int8 _enable
Definition: AP_NavEKF3.h:368
Interface definition for the various Ground Control System.
uint32_t getBodyFrameOdomDebug(int8_t instance, Vector3f &velInnov, Vector3f &velInnovVar) const
void getVelNED(Vector3f &vel) const
struct NavEKF3::@149 yaw_reset_data
void getTimingStatistics(struct ekf_timing &timing)
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
void getAccelBias(Vector3f &accelBias) const
bool use_compass(void) const
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
Definition: AP_NavEKF3.cpp:869
void getMagNED(Vector3f &magNED) const
void getFilterStatus(int8_t instance, nav_filter_status &status) const
const char * prearm_failure_reason(void) const
bool have_ekf_logging(void) const
Definition: AP_NavEKF3.h:352
AP_HAL::Util * util
Definition: HAL.h:115
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
Definition: AP_NavEKF3.cpp:965
bool getHeightControlLimit(float &height) const
bool InitialiseFilter(void)
Definition: AP_NavEKF3.cpp:620
void getQuaternion(Quaternion &quat) const
void getTiltError(float &ang) const
GCS & gcs()
#define POS_I_GATE_DEFAULT
Definition: AP_NavEKF3.cpp:101
void Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
Definition: LogFile.cpp:367
void getTimingStatistics(int8_t instance, struct ekf_timing &timing) const
void getGyroBias(Vector3f &gyroBias) const
void getFilterStatus(nav_filter_status &status) const
void resetGyroBias(void)
Definition: AP_NavEKF3.cpp:896
uint32_t _frameTimeUsec
Definition: AP_NavEKF3.h:364
#define VEL_I_GATE_DEFAULT
Definition: AP_NavEKF3.cpp:100
void setTerrainHgtStable(bool val)
uint8_t setInhibitGPS(void)
void getRotationBodyToNED(Matrix3f &mat) const
const Compass * get_compass() const
Definition: AP_AHRS.h:150
static AP_InertialSensor ins
Definition: AHRS_Test.cpp:18
bool use_compass(void) const
void setTouchdownExpected(bool val)
float errorScore(void) const
uint32_t getLastYawResetAngle(float &yawAng) const
void writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)
#define ALT_M_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:92
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
bool InitialiseFilterBootstrap(void)
void getWind(Vector3f &wind) const
void updateLaneSwitchYawResetData(uint8_t new_primary, uint8_t old_primary)
void resetGyroBias(void)
uint32_t getLastYawResetAngle(float &yawAngDelta)
void setTakeoffExpected(bool val)
bool getRangeBeaconDebug(uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow, Vector3f &posNED)
bool getHAGL(float &HAGL) const
uint32_t getLastPosNorthEastReset(Vector2f &pos) const
bool getLLH(struct Location &loc) const
NavEKF3_core * core
Definition: AP_NavEKF3.h:360
void updateLaneSwitchPosResetData(uint8_t new_primary, uint8_t old_primary)
#define VELD_M_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:90
void getVelNED(int8_t instance, Vector3f &vel) const
Definition: AP_NavEKF3.cpp:841
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
#define FLOW_I_GATE_DEFAULT
Definition: AP_NavEKF3.cpp:108
void Log_Write_Compass(const Compass &compass, uint64_t time_us=0)
Definition: LogFile.cpp:1479
uint8_t primary
Definition: AP_NavEKF3.h:359
void getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
void getEulerAngles(Vector3f &eulers) const
#define f(i)
#define MAGB_P_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:98
#define ACC_P_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:95
bool getPosD(int8_t instance, float &posD) const
Definition: AP_NavEKF3.cpp:831
int8_t getPrimaryCoreIMUIndex(void) const
Definition: AP_NavEKF3.cpp:808
void UpdateFilter(bool predict)
void getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
void getEulerAngles(int8_t instance, Vector3f &eulers) const
void setTakeoffExpected(bool val)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void check_log_write(void)
Definition: AP_NavEKF3.cpp:592
uint32_t getLastPosNorthEastReset(Vector2f &posDelta)
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
#define POSNE_M_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:91
uint64_t micros64()
Definition: system.cpp:162
void UpdateFilter(void)
Definition: AP_NavEKF3.cpp:720
uint64_t imuSampleTime_us
Definition: AP_NavEKF3.h:459
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
#define FLOW_MEAS_DELAY
Definition: AP_NavEKF3.cpp:106
AP_Int8 log_replay
Definition: DataFlash.h:200
uint32_t getLastPosDownReset(float &posD) const
void getFilterFaults(int8_t instance, uint16_t &faults) const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
void getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
Definition: AP_NavEKF3.cpp:986
uint16_t get_sample_rate(void) const
uint32_t getLastPosDownReset(float &posDelta)
#define CHECK_SCALER_DEFAULT
Definition: AP_NavEKF3.cpp:109
void Log_Write_GPS(uint8_t instance, uint64_t time_us=0)
Definition: LogFile.cpp:136
void getFilterGpsStatus(nav_gps_status &status) const
NavEKF3(const AP_AHRS *ahrs, const RangeFinder &rng)
Definition: AP_NavEKF3.cpp:582
AP_Int8 _imuMask
Definition: AP_NavEKF3.h:400
#define HGT_I_GATE_DEFAULT
Definition: AP_NavEKF3.cpp:102
bool coreSetupRequired[7]
Definition: AP_NavEKF3.h:483
void getFlowDebug(float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
#define MAG_CAL_DEFAULT
Definition: AP_NavEKF3.cpp:104
virtual void * malloc_type(size_t size, Memory_Type mem_type)
Definition: Util.h:115
bool getHAGL(float &HAGL) const
void getMagNED(int8_t instance, Vector3f &magNED) const
Definition: AP_NavEKF3.cpp:956
void writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)
uint8_t coreImuIndex[7]
Definition: AP_NavEKF3.h:484
bool getPosNE(int8_t instance, Vector2f &posNE) const
Definition: AP_NavEKF3.cpp:819
void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
bool healthy(void) const
void getQuaternion(int8_t instance, Quaternion &quat) const
int8_t getPrimaryCoreIndex(void) const
Definition: AP_NavEKF3.cpp:798
void zero()
Definition: vector2.h:125
#define MAG_M_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:93
void getStateVariances(float stateVar[24])
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
bool healthy(void) const
Definition: AP_NavEKF3.cpp:788
void getOutputTrackingError(Vector3f &error) const
bool getOriginLLH(int8_t instance, struct Location &loc) const
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
uint8_t setInhibitGPS(void)
Definition: AP_NavEKF3.cpp:929
#define error(fmt, args ...)
const char * prearm_failure_reason(void) const
void getMagXYZ(Vector3f &magXYZ) const
#define GYRO_P_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:94
#define FLOW_M_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:107
AP_InertialSensor & ins()
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
void getStateVariances(int8_t instance, float stateVar[24]) const
void getAccelNED(Vector3f &accelNED) const
void setTouchdownExpected(bool val)
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
Definition: AP_NavEKF3.cpp:939
bool getHeightControlLimit(float &height) const
float getPosDownDerivative(int8_t instance) const
Definition: AP_NavEKF3.cpp:850
void getAccelBias(int8_t instance, Vector3f &accelBias) const
Definition: AP_NavEKF3.cpp:878
bool getLLH(struct Location &loc) const
void getWind(int8_t instance, Vector3f &wind) const
Definition: AP_NavEKF3.cpp:947
uint8_t _framesPerPrediction
Definition: AP_NavEKF3.h:365
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
#define GBIAS_P_NSE_DEFAULT
Definition: AP_NavEKF3.cpp:96
void getOutputTrackingError(int8_t instance, Vector3f &error) const
bool runCoreSelection
Definition: AP_NavEKF3.h:482
uint32_t micros()
Definition: system.cpp:152
void send_status_report(mavlink_channel_t chan)
#define AP_GROUPEND
Definition: AP_Param.h:121
void Log_Write_Baro(uint64_t time_us=0)
Definition: LogFile.cpp:279
bool getOriginLLH(struct Location &loc) const
void setTerrainHgtStable(bool val)
uint8_t get_accel_count(void) const
friend class NavEKF3_core
Definition: AP_NavEKF3.h:35
uint8_t getActiveMag(int8_t instance) const
Definition: AP_NavEKF3.cpp:974
void getFilterTimeouts(uint8_t &timeouts) const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
const AP_AHRS * _ahrs
Definition: AP_NavEKF3.h:361
void updateLaneSwitchPosDownResetData(uint8_t new_primary, uint8_t old_primary)
void getAccelNED(Vector3f &accelNED) const
Definition: AP_NavEKF3.cpp:861
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)