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