APM:Libraries
AP_NavEKF3_VehicleStatus.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
4 
5 #include "AP_NavEKF3.h"
6 #include "AP_NavEKF3_core.h"
7 #include <AP_AHRS/AP_AHRS.h>
9 #include <GCS_MAVLink/GCS.h>
10 
11 extern const AP_HAL::HAL& hal;
12 
13 
14 /* Monitor GPS data to see if quality is good enough to initialise the EKF
15  Monitor magnetometer innovations to to see if the heading is good enough to use GPS
16  Return true if all criteria pass for 10 seconds
17 
18  We also record the failure reason so that prearm_failure_reason()
19  can give a good report to the user on why arming is failing
20 */
22 {
23  if (inFlight && assume_zero_sideslip() && !use_compass()) {
24  // this is a special case where a plane has launched without magnetometer
25  // is now in the air and needs to align yaw to the GPS and start navigating as soon as possible
26  return true;
27  }
28 
29  // User defined multiplier to be applied to check thresholds
30  float checkScaler = 0.01f*(float)frontend->_gpsCheckScaler;
31 
32  // If we have good magnetometer consistency and bad innovations for longer than 5 seconds then we reset heading and field states
33  // This enables us to handle large changes to the external magnetic field environment that occur before arming
34  if ((magTestRatio.x <= 1.0f && magTestRatio.y <= 1.0f && yawTestRatio <= 1.0f) || !consistentMagData) {
36  }
38  // request reset of heading and magnetic field states
39  magYawResetRequest = true;
40  // reset timer to ensure that bad magnetometer data cannot cause a heading reset more often than every 5 seconds
42  }
43 
44  // Check for significant change in GPS position if disarmed which indicates bad GPS
45  // This check can only be used when the vehicle is stationary
46  const AP_GPS &gps = AP::gps();
47 
48  const struct Location &gpsloc = gps.location(); // Current location
49  const float posFiltTimeConst = 10.0f; // time constant used to decay position drift
50  // calculate time lapsesd since last update and limit to prevent numerical errors
51  float deltaTime = constrain_float(float(imuDataDelayed.time_ms - lastPreAlignGpsCheckTime_ms)*0.001f,0.01f,posFiltTimeConst);
53  // Sum distance moved
55  gpsloc_prev = gpsloc;
56  // Decay distance moved exponentially to zero
57  gpsDriftNE *= (1.0f - deltaTime/posFiltTimeConst);
58  // Clamp the fiter state to prevent excessive persistence of large transients
59  gpsDriftNE = MIN(gpsDriftNE,10.0f);
60  // Fail if more than 3 metres drift after filtering whilst on-ground
61  // This corresponds to a maximum acceptable average drift rate of 0.3 m/s or single glitch event of 3m
62  bool gpsDriftFail = (gpsDriftNE > 3.0f*checkScaler) && onGround && (frontend->_gpsCheck & MASK_GPS_POS_DRIFT);
63 
64  // Report check result as a text string and bitmask
65  if (gpsDriftFail) {
67  sizeof(prearm_fail_string),
68  "GPS drift %.1fm (needs %.1f)", (double)gpsDriftNE, (double)(3.0f*checkScaler));
69  gpsCheckStatus.bad_horiz_drift = true;
70  } else {
71  gpsCheckStatus.bad_horiz_drift = false;
72  }
73 
74  // Check that the vertical GPS vertical velocity is reasonable after noise filtering
75  bool gpsVertVelFail;
76  if (gps.have_vertical_velocity() && onGround) {
77  // check that the average vertical GPS velocity is close to zero
78  gpsVertVelFilt = 0.1f * gpsDataNew.vel.z + 0.9f * gpsVertVelFilt;
80  gpsVertVelFail = (fabsf(gpsVertVelFilt) > 0.3f*checkScaler) && (frontend->_gpsCheck & MASK_GPS_VERT_SPD);
81  } else if ((frontend->_fusionModeGPS == 0) && !gps.have_vertical_velocity()) {
82  // If the EKF settings require vertical GPS velocity and the receiver is not outputting it, then fail
83  gpsVertVelFail = true;
84  // if we have a 3D fix with no vertical velocity and
85  // EK3_GPS_TYPE=0 then change it to 1. It means the GPS is not
86  // capable of giving a vertical velocity
87  if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
88  frontend->_fusionModeGPS.set(1);
89  gcs().send_text(MAV_SEVERITY_WARNING, "EK3: Changed EK3_GPS_TYPE to 1");
90  }
91  } else {
92  gpsVertVelFail = false;
93  }
94 
95  // Report check result as a text string and bitmask
96  if (gpsVertVelFail) {
98  sizeof(prearm_fail_string),
99  "GPS vertical speed %.2fm/s (needs %.2f)", (double)fabsf(gpsVertVelFilt), (double)(0.3f*checkScaler));
100  gpsCheckStatus.bad_vert_vel = true;
101  } else {
102  gpsCheckStatus.bad_vert_vel = false;
103  }
104 
105  // Check that the horizontal GPS vertical velocity is reasonable after noise filtering
106  // This check can only be used if the vehicle is stationary
107  bool gpsHorizVelFail;
108  if (onGround) {
111  gpsHorizVelFail = (fabsf(gpsHorizVelFilt) > 0.3f*checkScaler) && (frontend->_gpsCheck & MASK_GPS_HORIZ_SPD);
112  } else {
113  gpsHorizVelFail = false;
114  }
115 
116  // Report check result as a text string and bitmask
117  if (gpsHorizVelFail) {
119  sizeof(prearm_fail_string),
120  "GPS horizontal speed %.2fm/s (needs %.2f)", (double)gpsDriftNE, (double)(0.3f*checkScaler));
121  gpsCheckStatus.bad_horiz_vel = true;
122  } else {
123  gpsCheckStatus.bad_horiz_vel = false;
124  }
125 
126  // fail if horiziontal position accuracy not sufficient
127  float hAcc = 0.0f;
128  bool hAccFail;
129  if (gps.horizontal_accuracy(hAcc)) {
130  hAccFail = (hAcc > 5.0f*checkScaler) && (frontend->_gpsCheck & MASK_GPS_POS_ERR);
131  } else {
132  hAccFail = false;
133  }
134 
135  // Report check result as a text string and bitmask
136  if (hAccFail) {
138  sizeof(prearm_fail_string),
139  "GPS horiz error %.1fm (needs %.1f)", (double)hAcc, (double)(5.0f*checkScaler));
140  gpsCheckStatus.bad_hAcc = true;
141  } else {
142  gpsCheckStatus.bad_hAcc = false;
143  }
144 
145 
146  // Check for vertical GPS accuracy
147  float vAcc = 0.0f;
148  bool vAccFail = false;
149  if (gps.vertical_accuracy(vAcc)) {
150  vAccFail = (vAcc > 7.5f * checkScaler) && (frontend->_gpsCheck & MASK_GPS_POS_ERR);
151  }
152  // Report check result as a text string and bitmask
153  if (vAccFail) {
155  sizeof(prearm_fail_string),
156  "GPS vert error %.1fm (needs < %.1f)", (double)vAcc, (double)(7.5f * checkScaler));
157  gpsCheckStatus.bad_vAcc = true;
158  } else {
159  gpsCheckStatus.bad_vAcc = false;
160  }
161 
162  // fail if reported speed accuracy greater than threshold
163  bool gpsSpdAccFail = (gpsSpdAccuracy > 1.0f*checkScaler) && (frontend->_gpsCheck & MASK_GPS_SPD_ERR);
164 
165  // Report check result as a text string and bitmask
166  if (gpsSpdAccFail) {
168  sizeof(prearm_fail_string),
169  "GPS speed error %.1f (needs %.1f)", (double)gpsSpdAccuracy, (double)(1.0f*checkScaler));
170  gpsCheckStatus.bad_sAcc = true;
171  } else {
172  gpsCheckStatus.bad_sAcc = false;
173  }
174 
175  // fail if satellite geometry is poor
176  bool hdopFail = (gps.get_hdop() > 250) && (frontend->_gpsCheck & MASK_GPS_HDOP);
177 
178  // Report check result as a text string and bitmask
179  if (hdopFail) {
181  "GPS HDOP %.1f (needs 2.5)", (double)(0.01f * gps.get_hdop()));
182  gpsCheckStatus.bad_hdop = true;
183  } else {
184  gpsCheckStatus.bad_hdop = false;
185  }
186 
187  // fail if not enough sats
188  bool numSatsFail = (gps.num_sats() < 6) && (frontend->_gpsCheck & MASK_GPS_NSATS);
189 
190  // Report check result as a text string and bitmask
191  if (numSatsFail) {
193  "GPS numsats %u (needs 6)", gps.num_sats());
194  gpsCheckStatus.bad_sats = true;
195  } else {
196  gpsCheckStatus.bad_sats = false;
197  }
198 
199  // fail if magnetometer innovations are outside limits indicating bad yaw
200  // with bad yaw we are unable to use GPS
201  bool yawFail;
202  if ((magTestRatio.x > 1.0f || magTestRatio.y > 1.0f || yawTestRatio > 1.0f) && (frontend->_gpsCheck & MASK_GPS_YAW_ERR)) {
203  yawFail = true;
204  } else {
205  yawFail = false;
206  }
207 
208  // Report check result as a text string and bitmask
209  if (yawFail) {
211  sizeof(prearm_fail_string),
212  "Mag yaw error x=%.1f y=%.1f",
213  (double)magTestRatio.x,
214  (double)magTestRatio.y);
215  gpsCheckStatus.bad_yaw = true;
216  } else {
217  gpsCheckStatus.bad_yaw = false;
218  }
219 
220  // assume failed first time through and notify user checks have started
221  if (lastGpsVelFail_ms == 0) {
222  hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "EKF starting GPS checks");
224  }
225 
226  // record time of fail
227  if (gpsSpdAccFail || numSatsFail || hdopFail || hAccFail || vAccFail || yawFail || gpsDriftFail || gpsVertVelFail || gpsHorizVelFail) {
229  }
230 
231  // continuous period without fail required to return a healthy status
232  if (imuSampleTime_ms - lastGpsVelFail_ms > 10000) {
233  return true;
234  }
235  return false;
236 }
237 
238 // update inflight calculaton that determines if GPS data is good enough for reliable navigation
240 {
241  // use a simple criteria based on the GPS receivers claimed speed accuracy and the EKF innovation consistency checks
242 
243  // set up varaibles and constants used by filter that is applied to GPS speed accuracy
244  const float alpha1 = 0.2f; // coefficient for first stage LPF applied to raw speed accuracy data
245  const float tau = 10.0f; // time constant (sec) of peak hold decay
246  if (lastGpsCheckTime_ms == 0) {
248  }
249  float dtLPF = (imuSampleTime_ms - lastGpsCheckTime_ms) * 1e-3f;
251  float alpha2 = constrain_float(dtLPF/tau,0.0f,1.0f);
252 
253  // get the receivers reported speed accuracy
254  float gpsSpdAccRaw;
255  if (!AP::gps().speed_accuracy(gpsSpdAccRaw)) {
256  gpsSpdAccRaw = 0.0f;
257  }
258 
259  // filter the raw speed accuracy using a LPF
260  sAccFilterState1 = constrain_float((alpha1 * gpsSpdAccRaw + (1.0f - alpha1) * sAccFilterState1),0.0f,10.0f);
261 
262  // apply a peak hold filter to the LPF output
263  sAccFilterState2 = MAX(sAccFilterState1,((1.0f - alpha2) * sAccFilterState2));
264 
265  // Apply a threshold test with hysteresis to the filtered GPS speed accuracy data
266  if (sAccFilterState2 > 1.5f ) {
267  gpsSpdAccPass = false;
268  } else if(sAccFilterState2 < 1.0f) {
269  gpsSpdAccPass = true;
270  }
271 
272  // Apply a threshold test with hysteresis to the normalised position and velocity innovations
273  // Require a fail for one second and a pass for 10 seconds to transition
274  if (lastInnovFailTime_ms == 0) {
277  }
278  if (velTestRatio < 1.0f && posTestRatio < 1.0f) {
280  } else if (velTestRatio > 0.7f || posTestRatio > 0.7f) {
282  }
283  if ((imuSampleTime_ms - lastInnovPassTime_ms) > 1000) {
284  ekfInnovationsPass = false;
285  } else if ((imuSampleTime_ms - lastInnovFailTime_ms) > 10000) {
286  ekfInnovationsPass = true;
287  }
288 
289  // both GPS speed accuracy and EKF innovations must pass
291 }
292 
293 // Detect if we are in flight or on ground
295 {
296  /*
297  If we are a fly forward type vehicle (eg plane), then in-air status can be determined through a combination of speed and height criteria.
298  Because of the differing certainty requirements of algorithms that need the in-flight / on-ground status we use two booleans where
299  onGround indicates a high certainty we are not flying and inFlight indicates a high certainty we are flying. It is possible for
300  both onGround and inFlight to be false if the status is uncertain, but they cannot both be true.
301 
302  If we are a plane as indicated by the assume_zero_sideslip() status, then different logic is used
303 
304  TODO - this logic should be moved out of the EKF and into the flight vehicle code.
305  */
306 
307  if (assume_zero_sideslip()) {
308  // To be confident we are in the air we use a criteria which combines arm status, ground speed, airspeed and height change
309  float gndSpdSq = sq(gpsDataDelayed.vel.x) + sq(gpsDataDelayed.vel.y);
310  bool highGndSpd = false;
311  bool highAirSpd = false;
312  bool largeHgtChange = false;
313 
314  // trigger at 8 m/s airspeed
317  if (airspeed->get_airspeed() * airspeed->get_EAS2TAS() > 10.0f) {
318  highAirSpd = true;
319  }
320  }
321 
322  // trigger at 10 m/s GPS velocity, but not if GPS is reporting bad velocity errors
323  if (gndSpdSq > 100.0f && gpsSpdAccuracy < 1.0f) {
324  highGndSpd = true;
325  }
326 
327  // trigger if more than 10m away from initial height
328  if (fabsf(hgtMea) > 10.0f) {
329  largeHgtChange = true;
330  }
331 
332  // Determine to a high certainty we are flying
333  if (motorsArmed && highGndSpd && (highAirSpd || largeHgtChange)) {
334  onGround = false;
335  inFlight = true;
336  }
337 
338  // if is possible we are in flight, set the time this condition was last detected
339  if (motorsArmed && (highGndSpd || highAirSpd || largeHgtChange)) {
341  onGround = false;
342  }
343 
344  // Determine to a high certainty we are not flying
345  // after 5 seconds of not detecting a possible flight condition or we are disarmed, we transition to on-ground mode
346  if(!motorsArmed || ((imuSampleTime_ms - airborneDetectTime_ms) > 5000)) {
347  onGround = true;
348  inFlight = false;
349  }
350  } else {
351  // Non fly forward vehicle, so can only use height and motor arm status
352 
353  // If the motors are armed then we could be flying and if they are not armed then we are definitely not flying
354  if (motorsArmed) {
355  onGround = false;
356  } else {
357  inFlight = false;
358  onGround = true;
359  }
360 
361  if (!onGround) {
362  // If height has increased since exiting on-ground, then we definitely are flying
363  if ((stateStruct.position.z - posDownAtTakeoff) < -1.5f) {
364  inFlight = true;
365  }
366 
367  // If rangefinder has increased since exiting on-ground, then we definitely are flying
368  if ((rangeDataNew.rng - rngAtStartOfFlight) > 0.5f) {
369  inFlight = true;
370  }
371 
372  // If more than 5 seconds since likely_flying was set
373  // true, then set inFlight true
374  if (_ahrs->get_time_flying_ms() > 5000) {
375  inFlight = true;
376  }
377  }
378 
379  }
380 
381  // store current on-ground and in-air status for next time
384 
385  // Store vehicle height and range prior to takeoff for use in post takeoff checks
386  if (onGround) {
387  // store vertical position at start of flight to use as a reference for ground relative checks
389  // store the range finder measurement which will be used as a reference to detect when we have taken off
391  // if the magnetic field states have been set, then continue to update the vertical position
392  // quaternion and yaw innovation snapshots to use as a reference when we start to fly.
393  if (magStateInitComplete) {
397  }
398  }
399 
400 }
401 
402 
403 // determine if a takeoff is expected so that we can compensate for expected barometer errors due to ground effect
405 {
407  expectGndEffectTakeoff = false;
408  }
409 
410  return expectGndEffectTakeoff;
411 }
412 
413 // called by vehicle code to specify that a takeoff is happening
414 // causes the EKF to compensate for expected barometer errors due to ground effect
416 {
419 }
420 
421 
422 // determine if a touchdown is expected so that we can compensate for expected barometer errors due to ground effect
424 {
426  expectGndEffectTouchdown = false;
427  }
428 
430 }
431 
432 // called by vehicle code to specify that a touchdown is expected to happen
433 // causes the EKF to compensate for expected barometer errors due to ground effect
435 {
438 }
439 
440 // Set to true if the terrain underneath is stable enough to be used as a height reference
441 // in combination with a range finder. Set to false if the terrain underneath the vehicle
442 // cannot be used as a height reference
444 {
446  terrainHgtStable = val;
447 }
448 
449 // Detect takeoff for optical flow navigation
451 {
452  if (!onGround && !takeOffDetected && (imuSampleTime_ms - timeAtArming_ms) > 1000) {
453  // we are no longer confidently on the ground so check the range finder and gyro for signs of takeoff
454  const AP_InertialSensor &ins = AP::ins();
455  Vector3f angRateVec;
456  Vector3f gyroBias;
457  getGyroBias(gyroBias);
458  bool dual_ins = ins.get_gyro_health(0) && ins.get_gyro_health(1);
459  if (dual_ins) {
460  angRateVec = (ins.get_gyro(0) + ins.get_gyro(1)) * 0.5f - gyroBias;
461  } else {
462  angRateVec = ins.get_gyro() - gyroBias;
463  }
464 
465  takeOffDetected = (takeOffDetected || (angRateVec.length() > 0.1f) || (rangeDataNew.rng > (rngAtStartOfFlight + 0.1f)));
466  } else if (onGround) {
467  // we are confidently on the ground so set the takeoff detected status to false
468  takeOffDetected = false;
469  }
470 }
471 
472 #endif // HAL_CPU_CLASS
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
Definition: AP_GPS.h:48
char prearm_fail_string[40]
AP_Int8 _gpsCheck
Definition: AP_NavEKF3.h:399
gps_elements gpsDataDelayed
AP_Int8 _fusionModeGPS
Definition: AP_NavEKF3.h:384
float tau
Definition: AP_AutoTune.cpp:94
uint32_t terrainHgtStableSet_ms
bool magStateInitComplete
uint32_t lastInnovPassTime_ms
Quaternion quatAtLastMagReset
bool expectGndEffectTouchdown
imu_elements imuDataDelayed
const Vector3f & get_gyro(uint8_t i) const
uint32_t timeAtArming_ms
Interface definition for the various Ground Control System.
gps_elements gpsDataNew
bool assume_zero_sideslip(void) const
float get_airspeed(uint8_t i) const
Definition: AP_Airspeed.h:53
const AP_AHRS * _ahrs
range_elements rangeDataNew
AP_HAL::Util * util
Definition: HAL.h:115
GCS & gcs()
void getGyroBias(Vector3f &gyroBias) const
const Location & location(uint8_t instance) const
Definition: AP_GPS.h:200
float posDownAtLastMagReset
#define MIN(a, b)
Definition: usb_conf.h:215
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
struct NavEKF3_core::state_elements & stateStruct
float rngAtStartOfFlight
static AP_InertialSensor ins
Definition: AHRS_Test.cpp:18
bool use_compass(void) const
const AP_Airspeed * get_airspeed(void) const
Definition: AP_AHRS.h:174
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
bool expectGndEffectTakeoff
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 f(i)
float yawInnovAtLastMagReset
#define MASK_GPS_HDOP
T y
Definition: vector3.h:67
uint32_t lastPreAlignGpsCheckTime_ms
#define MASK_GPS_SPD_ERR
void setTakeoffExpected(bool val)
T z
Definition: vector3.h:67
#define MASK_GPS_HORIZ_SPD
uint16_t get_hdop(uint8_t instance) const
Definition: AP_GPS.h:284
struct Location gpsloc_prev
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
uint32_t magYawResetTimer_ms
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
#define MASK_GPS_NSATS
float length(void) const
Definition: vector3.cpp:288
uint32_t lastGpsCheckTime_ms
float length(void) const
Definition: vector2.cpp:24
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
struct NavEKF3_core::@154 gpsCheckStatus
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
float get_EAS2TAS(uint8_t i) const
Definition: AP_Airspeed.h:123
Vector3f magTestRatio
uint8_t num_sats(uint8_t instance) const
Definition: AP_GPS.h:260
uint32_t touchdownExpectedSet_ms
int snprintf(char *str, size_t size, const char *format,...)
Definition: Util.cpp:44
float sAccFilterState2
float sAccFilterState1
uint32_t takeoffExpectedSet_ms
#define MASK_GPS_POS_ERR
float sq(const T val)
Definition: AP_Math.h:170
uint32_t get_time_flying_ms(void) const
Definition: AP_AHRS.h:126
const uint16_t gndEffectTimeout_ms
Definition: AP_NavEKF3.h:444
AP_InertialSensor & ins()
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
#define MASK_GPS_POS_DRIFT
void setTouchdownExpected(bool val)
bool get_gyro_health(uint8_t instance) const
bool airspeed_sensor_enabled(void) const
Definition: AP_AHRS.h:299
static AP_GPS gps
Definition: AHRS_Test.cpp:22
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
bool vertical_accuracy(uint8_t instance, float &vacc) const
Definition: AP_GPS.cpp:334
NavEKF3 * frontend
bool horizontal_accuracy(uint8_t instance, float &hacc) const
Definition: AP_GPS.cpp:325
float posDownAtTakeoff
uint32_t imuSampleTime_ms
#define MASK_GPS_VERT_SPD
#define MASK_GPS_YAW_ERR
uint32_t lastGpsVelFail_ms
T x
Definition: vector3.h:67
void setTerrainHgtStable(bool val)
uint32_t airborneDetectTime_ms
AP_Int16 _gpsCheckScaler
Definition: AP_NavEKF3.h:401
bool have_vertical_velocity(uint8_t instance) const
Definition: AP_GPS.h:326
uint32_t lastInnovFailTime_ms