APM:Libraries
AP_NavEKF3_Control.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 // Control filter mode transitions
16 {
17  // Determine motor arm status
20  if (motorsArmed && !prevMotorsArmed) {
21  // set the time at which we arm to assist with checks
23  }
24 
25  // Detect if we are in flight on or ground
26  detectFlight();
27 
28  // Determine if learning of wind and magnetic field will be enabled and set corresponding indexing limits to
29  // avoid unnecessary operations
31 
32  // Check the alignmnent status of the tilt and yaw attitude
33  // Used during initial bootstrap alignment of the filter
35 
36  // Set the type of inertial navigation aiding used
37  setAidingMode();
38 
39 }
40 
41 /*
42  return effective value for _magCal for this core
43  */
44 uint8_t NavEKF3_core::effective_magCal(void) const
45 {
46  // force use of simple magnetic heading fusion for specified cores
47  if (frontend->_magMask & core_index) {
48  return 2;
49  } else {
50  return frontend->_magCal;
51  }
52 }
53 
54 // Determine if learning of wind and magnetic field will be enabled and set corresponding indexing limits to
55 // avoid unnecessary operations
57 {
58  // If we are on ground, or in constant position mode, or don't have the right vehicle and sensing to estimate wind, inhibit wind states
59  bool setWindInhibit = (!useAirspeed() && !assume_zero_sideslip()) || onGround || (PV_AidingMode == AID_NONE);
60  if (!inhibitWindStates && setWindInhibit) {
61  inhibitWindStates = true;
63  } else if (inhibitWindStates && !setWindInhibit) {
64  inhibitWindStates = false;
66  // set states and variances
67  if (yawAlignComplete && useAirspeed()) {
68  // if we have airspeed and a valid heading, set the wind states to the reciprocal of the vehicle heading
69  // which assumes the vehicle has launched into the wind
70  Vector3f tempEuler;
71  stateStruct.quat.to_euler(tempEuler.x, tempEuler.y, tempEuler.z);
72  float windSpeed = sqrtf(sq(stateStruct.velocity.x) + sq(stateStruct.velocity.y)) - tasDataDelayed.tas;
73  stateStruct.wind_vel.x = windSpeed * cosf(tempEuler.z);
74  stateStruct.wind_vel.y = windSpeed * sinf(tempEuler.z);
75 
76  // set the wind sate variances to the measurement uncertainty
77  for (uint8_t index=22; index<=23; index++) {
78  P[index][index] = sq(constrain_float(frontend->_easNoise, 0.5f, 5.0f) * constrain_float(_ahrs->get_EAS2TAS(), 0.9f, 10.0f));
79  }
80  } else {
81  // set the variances using a typical wind speed
82  for (uint8_t index=22; index<=23; index++) {
83  P[index][index] = sq(5.0f);
84  }
85  }
86  }
87 
88  // determine if the vehicle is manoevring
89  if (accNavMagHoriz > 0.5f) {
90  manoeuvring = true;
91  } else {
92  manoeuvring = false;
93  }
94 
95  // Determine if learning of magnetic field states has been requested by the user
96  uint8_t magCal = effective_magCal();
97  bool magCalRequested =
98  ((magCal == 0) && inFlight) || // when flying
99  ((magCal == 1) && manoeuvring) || // when manoeuvring
100  ((magCal == 3) && finalInflightYawInit && finalInflightMagInit) || // when initial in-air yaw and mag field reset is complete
101  (magCal == 4); // all the time
102 
103  // Deny mag calibration request if we aren't using the compass, it has been inhibited by the user,
104  // we do not have an absolute position reference or are on the ground (unless explicitly requested by the user)
105  bool magCalDenied = !use_compass() || (magCal == 2) || (onGround && magCal != 4);
106 
107  // Inhibit the magnetic field calibration if not requested or denied
108  bool setMagInhibit = !magCalRequested || magCalDenied;
109  if (!inhibitMagStates && setMagInhibit) {
110  inhibitMagStates = true;
112  } else if (inhibitMagStates && !setMagInhibit) {
113  inhibitMagStates = false;
115  if (magFieldLearned) {
116  // if we have already learned the field states, then retain the learned variances
117  P[16][16] = earthMagFieldVar.x;
118  P[17][17] = earthMagFieldVar.y;
119  P[18][18] = earthMagFieldVar.z;
120  P[19][19] = bodyMagFieldVar.x;
121  P[20][20] = bodyMagFieldVar.y;
122  P[21][21] = bodyMagFieldVar.z;
123  } else {
124  // set the variances equal to the observation variances
125  for (uint8_t index=18; index<=21; index++) {
126  P[index][index] = sq(frontend->_magNoise);
127  }
128 
129  // set the NE earth magnetic field states using the published declination
130  // and set the corresponding variances and covariances
132 
133  }
134  // request a reset of the yaw and magnetic field states if not done before
136  magYawResetRequest = true;
137  }
138  }
139 
140  // inhibit delta velocity bias learning if we have not yet aligned the tilt
142  // activate the states
143  inhibitDelVelBiasStates = false;
145 
146  // set the initial covariance values
148  P[14][14] = P[13][13];
149  P[15][15] = P[13][13];
150  }
151 
153  // activate the states
154  inhibitDelAngBiasStates = false;
156 
157  // set the initial covariance values
159  P[11][11] = P[10][10];
160  P[12][12] = P[10][10];
161  }
162 
163  // If on ground we clear the flag indicating that the magnetic field in-flight initialisation has been completed
164  // because we want it re-done for each takeoff
165  if (onGround) {
166  finalInflightYawInit = false;
167  finalInflightMagInit = false;
168  }
169 
171 }
172 
173 // Adjust the indexing limits used to address the covariance, states and other EKF arrays to avoid unnecessary operations
174 // if we are not using those states
176 {
177  if (inhibitWindStates) {
178  if (inhibitMagStates) {
181  stateIndexLim = 9;
182  } else {
183  stateIndexLim = 12;
184  }
185  } else {
186  stateIndexLim = 15;
187  }
188  } else {
189  stateIndexLim = 21;
190  }
191  } else {
192  stateIndexLim = 23;
193  }
194 }
195 
196 // Set inertial navigation aiding mode
198 {
199  // Save the previous status so we can detect when it has changed
201 
202  // Check that the gyro bias variance has converged
204 
205  // Determine if we should change aiding mode
206  switch (PV_AidingMode) {
207  case AID_NONE: {
208  // Don't allow filter to start position or velocity aiding until the tilt and yaw alignment is complete
209  // and IMU gyro bias estimates have stabilised
210  // If GPS usage has been prohiited then we use flow aiding provided optical flow data is present
211  // GPS aiding is the preferred option unless excluded by the user
214  } else if (readyToUseOptFlow() || readyToUseBodyOdm()) {
216  }
217  break;
218  }
219  case AID_RELATIVE: {
220  // Check if the fusion has timed out (flow measurements have been rejected for too long)
221  bool flowFusionTimeout = ((imuSampleTime_ms - prevFlowFuseTime_ms) > 5000);
222  // Check if the fusion has timed out (body odometry measurements have been rejected for too long)
223  bool bodyOdmFusionTimeout = ((imuSampleTime_ms - prevBodyVelFuseTime_ms) > 5000);
224  // Enable switch to absolute position mode if GPS or range beacon data is available
225  // If GPS or range beacons data is not available and flow fusion has timed out, then fall-back to no-aiding
228  } else if (flowFusionTimeout && bodyOdmFusionTimeout) {
230  }
231  break;
232  }
233  case AID_ABSOLUTE: {
234  // Find the minimum time without data required to trigger any check
236 
237  // Check if optical flow data is being used
238  bool optFlowUsed = (imuSampleTime_ms - prevFlowFuseTime_ms <= minTestTime_ms);
239 
240  // Check if body odometry data is being used
241  bool bodyOdmUsed = (imuSampleTime_ms - prevBodyVelFuseTime_ms <= minTestTime_ms);
242 
243  // Check if airspeed data is being used
244  bool airSpdUsed = (imuSampleTime_ms - lastTasPassTime_ms <= minTestTime_ms);
245 
246  // Check if range beacon data is being used
247  bool rngBcnUsed = (imuSampleTime_ms - lastRngBcnPassTime_ms <= minTestTime_ms);
248 
249  // Check if GPS is being used
250  bool gpsPosUsed = (imuSampleTime_ms - lastPosPassTime_ms <= minTestTime_ms);
251  bool gpsVelUsed = (imuSampleTime_ms - lastVelPassTime_ms <= minTestTime_ms);
252 
253  // Check if attitude drift has been constrained by a measurement source
254  bool attAiding = gpsPosUsed || gpsVelUsed || optFlowUsed || airSpdUsed || rngBcnUsed || bodyOdmUsed;
255 
256  // check if velocity drift has been constrained by a measurement source
257  bool velAiding = gpsVelUsed || airSpdUsed || optFlowUsed || bodyOdmUsed;
258 
259  // check if position drift has been constrained by a measurement source
260  bool posAiding = gpsPosUsed || rngBcnUsed;
261 
262  // Check if the loss of attitude aiding has become critical
263  bool attAidLossCritical = false;
264  if (!attAiding) {
265  attAidLossCritical = (imuSampleTime_ms - prevFlowFuseTime_ms > frontend->tiltDriftTimeMax_ms) &&
266  (imuSampleTime_ms - lastTasPassTime_ms > frontend->tiltDriftTimeMax_ms) &&
267  (imuSampleTime_ms - lastRngBcnPassTime_ms > frontend->tiltDriftTimeMax_ms) &&
268  (imuSampleTime_ms - lastPosPassTime_ms > frontend->tiltDriftTimeMax_ms) &&
269  (imuSampleTime_ms - lastVelPassTime_ms > frontend->tiltDriftTimeMax_ms);
270  }
271 
272  // Check if the loss of position accuracy has become critical
273  bool posAidLossCritical = false;
274  if (!posAiding ) {
275  uint16_t maxLossTime_ms;
276  if (!velAiding) {
277  maxLossTime_ms = frontend->posRetryTimeNoVel_ms;
278  } else {
279  maxLossTime_ms = frontend->posRetryTimeUseVel_ms;
280  }
281  posAidLossCritical = (imuSampleTime_ms - lastRngBcnPassTime_ms > maxLossTime_ms) &&
282  (imuSampleTime_ms - lastPosPassTime_ms > maxLossTime_ms);
283  }
284 
285  if (attAidLossCritical) {
286  // if the loss of attitude data is critical, then put the filter into a constant position mode
288  posTimeout = true;
289  velTimeout = true;
290  rngBcnTimeout = true;
291  tasTimeout = true;
292  gpsNotAvailable = true;
293  } else if (posAidLossCritical) {
294  // if the loss of position is critical, declare all sources of position aiding as being timed out
295  posTimeout = true;
296  velTimeout = true;
297  rngBcnTimeout = true;
298  gpsNotAvailable = true;
299  }
300  break;
301  }
302  }
303 
304  // check to see if we are starting or stopping aiding and set states and modes as required
306  // set various usage modes based on the condition when we start aiding. These are then held until aiding is stopped.
307  switch (PV_AidingMode) {
308  case AID_NONE:
309  // We have ceased aiding
310  gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 IMU%u stopped aiding",(unsigned)imu_index);
311  // When not aiding, estimate orientation & height fusing synthetic constant position and zero velocity measurement to constrain tilt errors
312  posTimeout = true;
313  velTimeout = true;
314  // Reset the normalised innovation to avoid false failing bad fusion tests
315  velTestRatio = 0.0f;
316  posTestRatio = 0.0f;
317  // store the current position to be used to keep reporting the last known position
320  // initialise filtered altitude used to provide a takeoff reference to current baro on disarm
321  // this reduces the time required for the baro noise filter to settle before the filtered baro data can be used
323  // reset the vertical position state to faster recover from baro errors experienced during touchdown
325  // reset relative aiding sensor fusion activity status
326  flowFusionActive = false;
327  bodyVelFusionActive = false;
328  break;
329 
330  case AID_RELATIVE:
331  // We are doing relative position navigation where velocity errors are constrained, but position drift will occur
332  gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u started relative aiding",(unsigned)imu_index);
333  if (readyToUseOptFlow()) {
334  // Reset time stamps
337  } else if (readyToUseBodyOdm()) {
338  // Reset time stamps
341  }
342  posTimeout = true;
343  velTimeout = true;
344  break;
345 
346  case AID_ABSOLUTE:
347  if (readyToUseGPS()) {
348  // We are commencing aiding using GPS - this is the preferred method
351  gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u is using GPS",(unsigned)imu_index);
352  } else if (readyToUseRangeBeacon()) {
353  // We are commencing aiding using range beacons
356  gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u is using range beacons",(unsigned)imu_index);
357  gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u initial pos NE = %3.1f,%3.1f (m)",(unsigned)imu_index,(double)receiverPos.x,(double)receiverPos.y);
358  gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u initial beacon pos D offset = %3.1f (m)",(unsigned)imu_index,(double)bcnPosOffsetNED.z);
359  }
360 
361  // clear timeout flags as a precaution to avoid triggering any additional transitions
362  posTimeout = false;
363  velTimeout = false;
364 
365  // reset the last fusion accepted times to prevent unwanted activation of timeout logic
369  break;
370 
371  default:
372  break;
373  }
374 
375  // Always reset the position and velocity when changing mode
376  ResetVelocity();
377  ResetPosition();
378 
379  }
380 
381 }
382 
383 // Check the tilt and yaw alignmnent status
384 // Used during initial bootstrap alignment of the filter
386 {
387  // Check for tilt convergence - used during initial alignment
388  // Once the tilt variances have reduced to equivalent of 3deg uncertainty, re-set the yaw and magnetic field states
389  // and declare the tilt alignment complete
390  if (!tiltAlignComplete) {
391  Vector3f angleErrVarVec = calcRotVecVariances();
392  if ((angleErrVarVec.x + angleErrVarVec.y) < sq(0.05235f)) {
393  tiltAlignComplete = true;
394  gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u tilt alignment complete",(unsigned)imu_index);
395  }
396  }
397 
398  // submit yaw and magnetic field reset request
400  magYawResetRequest = true;
401  }
402 }
403 
404 // return true if we should use the airspeed sensor
406 {
407  return _ahrs->airspeed_sensor_enabled();
408 }
409 
410 // return true if we should use the range finder sensor
412 {
413  // TO-DO add code to set this based in setting of optical flow use parameter and presence of sensor
414  return true;
415 }
416 
417 // return true if the filter is ready to start using optical flow measurements
419 {
420  // We need stable roll/pitch angles and gyro bias estimates but do not need the yaw angle aligned to use optical flow
422 }
423 
424 // return true if the filter is ready to start using body frame odometry measurements
426 {
427 
428  // Check for fresh visual odometry data that meets the accuracy required for alignment
429  bool visoDataGood = (imuSampleTime_ms - bodyOdmMeasTime_ms < 200) && (bodyOdmDataNew.velErr < 1.0f);
430 
431  // Check for fresh wheel encoder data
432  bool wencDataGood = (imuSampleTime_ms - wheelOdmMeasTime_ms < 200);
433 
434  // We require stable roll/pitch angles and gyro bias estimates but do not need the yaw angle aligned to use odometry measurements
435  // becasue they are in a body frame of reference
436  return (visoDataGood || wencDataGood)
439 }
440 
441 // return true if the filter to be ready to use gps
443 {
445 }
446 
447 // return true if the filter to be ready to use the beacon range measurements
449 {
451 }
452 
453 // return true if we should use the compass
455 {
457 }
458 
459 /*
460  should we assume zero sideslip?
461  */
463 {
464  // we don't assume zero sideslip for ground vehicles as EKF could
465  // be quite sensitive to a rapid spin of the ground vehicle if
466  // traction is lost
468 }
469 
470 // set the LLH location of the filters NED origin
472 {
473  if (PV_AidingMode == AID_ABSOLUTE) {
474  return false;
475  }
476  EKF_origin = loc;
477  ekfGpsRefHgt = (double)0.01 * (double)EKF_origin.alt;
478  // define Earth rotation vector in the NED navigation frame at the origin
480  validOrigin = true;
481  return true;
482 }
483 
484 // Set the NED origin to be used until the next filter reset
486 {
487  // assume origin at current GPS location (no averaging)
489  // if flying, correct for height change from takeoff so that the origin is at field elevation
490  if (inFlight) {
491  EKF_origin.alt += (int32_t)(100.0f * stateStruct.position.z);
492  }
493  ekfGpsRefHgt = (double)0.01 * (double)EKF_origin.alt;
494  // define Earth rotation vector in the NED navigation frame at the origin
496  validOrigin = true;
497  gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u Origin set to GPS",(unsigned)imu_index);
498 }
499 
500 // record a yaw reset event
502 {
503  yawAlignComplete = true;
504  if (inFlight) {
505  finalInflightYawInit = true;
506  }
507 }
508 
509 // set the class variable true if the delta angle bias variances are sufficiently small
511 {
512  // check delta angle bias variances
513  const float delAngBiasVarMax = sq(radians(0.15f * dtEkfAvg));
514  delAngBiasLearned = (P[10][10] <= delAngBiasVarMax) &&
515  (P[11][11] <= delAngBiasVarMax) &&
516  (P[12][12] <= delAngBiasVarMax);
517 }
518 
519 // Commands the EKF to not use GPS.
520 // This command must be sent prior to vehicle arming and EKF commencement of GPS usage
521 // Returns 0 if command rejected
522 // Returns 1 if command accepted
524 {
526  return 0;
527  } else {
528  gpsInhibit = true;
529  return 1;
530  }
531 }
532 
533 // Update the filter status
535 {
536  // init return value
537  filterStatus.value = 0;
538  bool doingBodyVelNav = (PV_AidingMode != AID_NONE) && (imuSampleTime_ms - prevBodyVelFuseTime_ms < 5000);
539  bool doingFlowNav = (PV_AidingMode != AID_NONE) && flowDataValid;
540  bool doingWindRelNav = !tasTimeout && assume_zero_sideslip();
541  bool doingNormalGpsNav = !posTimeout && (PV_AidingMode == AID_ABSOLUTE);
542  bool someVertRefData = (!velTimeout && useGpsVertVel) || !hgtTimeout;
543  bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav || doingBodyVelNav;
544  bool filterHealthy = healthy() && tiltAlignComplete && (yawAlignComplete || (!use_compass() && (PV_AidingMode != AID_ABSOLUTE)));
545 
546  // If GPS height usage is specified, height is considered to be inaccurate until the GPS passes all checks
547  bool hgtNotAccurate = (frontend->_altSource == 2) && !validOrigin;
548 
549  // set individual flags
550  filterStatus.flags.attitude = !stateStruct.quat.is_nan() && filterHealthy; // attitude valid (we need a better check)
551  filterStatus.flags.horiz_vel = someHorizRefData && filterHealthy; // horizontal velocity estimate valid
552  filterStatus.flags.vert_vel = someVertRefData && filterHealthy; // vertical velocity estimate valid
553  filterStatus.flags.horiz_pos_rel = ((doingFlowNav && gndOffsetValid) || doingWindRelNav || doingNormalGpsNav || doingBodyVelNav) && filterHealthy; // relative horizontal position estimate valid
554  filterStatus.flags.horiz_pos_abs = doingNormalGpsNav && filterHealthy; // absolute horizontal position estimate valid
555  filterStatus.flags.vert_pos = !hgtTimeout && filterHealthy && !hgtNotAccurate; // vertical position estimate valid
556  filterStatus.flags.terrain_alt = gndOffsetValid && filterHealthy; // terrain height estimate valid
557  filterStatus.flags.const_pos_mode = (PV_AidingMode == AID_NONE) && filterHealthy; // constant position mode
558  filterStatus.flags.pred_horiz_pos_rel = filterStatus.flags.horiz_pos_rel; // EKF3 enters the required mode before flight
559  filterStatus.flags.pred_horiz_pos_abs = filterStatus.flags.horiz_pos_abs; // EKF3 enters the required mode before flight
560  filterStatus.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected
561  filterStatus.flags.takeoff = expectGndEffectTakeoff; // The EKF has been told to expect takeoff and is in a ground effect mitigation mode
562  filterStatus.flags.touchdown = expectGndEffectTouchdown; // The EKF has been told to detect touchdown and is in a ground effect mitigation mode
563  filterStatus.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE);
564  filterStatus.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE) && (frontend->_fusionModeGPS != 3); // GPS glitching is affecting navigation accuracy
565 }
566 
567 #endif // HAL_CPU_CLASS
uint8_t magSelectIndex
void to_euler(float &roll, float &pitch, float &yaw) const
Definition: quaternion.cpp:272
bool get_soft_armed() const
Definition: Util.h:15
void setWindMagStateLearningMode()
uint32_t lastPosPassTime_ms
AP_Int8 _fusionModeGPS
Definition: AP_NavEKF3.h:384
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
baro_elements baroDataDelayed
uint32_t prevFlowFuseTime_ms
bool magStateInitComplete
AP_Int8 _magMask
Definition: AP_NavEKF3.h:414
void updateStateIndexLim(void)
bool expectGndEffectTouchdown
uint32_t timeAtArming_ms
bool setOriginLLH(const Location &loc)
Interface definition for the various Ground Control System.
bool assume_zero_sideslip(void) const
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
AP_Float _easNoise
Definition: AP_NavEKF3.h:374
uint32_t wheelOdmMeasTime_ms
const AP_AHRS * _ahrs
AHRS_VehicleClass get_vehicle_class(void) const
Definition: AP_AHRS.h:133
float InitialGyroBiasUncertainty(void) const
bool readyToUseBodyOdm(void) const
AP_HAL::Util * util
Definition: HAL.h:115
uint32_t lastVelPassTime_ms
uint32_t lastTasPassTime_ms
GCS & gcs()
void checkGyroCalStatus(void)
uint32_t lastbodyVelPassTime_ms
AP_Float _magNoise
Definition: AP_NavEKF3.h:373
AidingMode PV_AidingMode
tas_elements tasDataDelayed
uint8_t effective_magCal(void) const
const Location & location(uint8_t instance) const
Definition: AP_GPS.h:200
uint32_t lastRngBcnPassTime_ms
uint32_t flowValidMeaTime_ms
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
bool readyToUseOptFlow(void) const
#define MIN(a, b)
Definition: usb_conf.h:215
AP_Int8 _altSource
Definition: AP_NavEKF3.h:397
uint8_t setInhibitGPS(void)
struct NavEKF3_core::state_elements & stateStruct
bool inhibitDelAngBiasStates
const Compass * get_compass() const
Definition: AP_AHRS.h:150
bool use_compass(void) const
T y
Definition: vector2.h:37
uint32_t flowMeaTime_ms
Vector3f bcnPosOffsetNED
Vector3f calcRotVecVariances(void)
bool readyToUseGPS(void) const
bool readyToUseRangeBeacon(void) const
Vector2f lastKnownPositionNE
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
AidingMode PV_AidingModePrev
bool expectGndEffectTakeoff
#define f(i)
AP_Int8 _magCal
Definition: AP_NavEKF3.h:390
T y
Definition: vector3.h:67
resetDataSource velResetSource
Vector3f earthMagFieldVar
T z
Definition: vector3.h:67
uint8_t stateIndexLim
void updateFilterStatus(void)
#define ACCEL_BIAS_LIM_SCALER
uint8_t core_index
Vector3f bodyMagFieldVar
bool allMagSensorsFailed
resetDataSource posResetSource
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
vel_odm_elements bodyOdmDataNew
bool inhibitDelVelBiasStates
struct nav_filter_status::@138 flags
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
AP_Float _accBiasLim
Definition: AP_NavEKF3.h:413
bool healthy(void) const
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void calcEarthRateNED(Vector3f &omega, int32_t latitude) const
void checkAttitudeAlignmentStatus()
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
bool rngBcnAlignmentCompleted
bool get_fly_forward(void) const
Definition: AP_AHRS.h:97
float sq(const T val)
Definition: AP_Math.h:170
const uint16_t posRetryTimeNoVel_ms
Definition: AP_NavEKF3.h:429
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
bool airspeed_sensor_enabled(void) const
Definition: AP_AHRS.h:299
float get_EAS2TAS(void) const
Definition: AP_AHRS.h:290
Vector3f earthRateNED
bool is_nan(void) const
Definition: quaternion.h:59
const uint16_t tiltDriftTimeMax_ms
Definition: AP_NavEKF3.h:427
const uint16_t posRetryTimeUseVel_ms
Definition: AP_NavEKF3.h:428
struct Location EKF_origin
uint32_t bodyOdmMeasTime_ms
NavEKF3 * frontend
nav_filter_status filterStatus
bool useRngFinder(void) const
uint32_t imuSampleTime_ms
uint32_t prevBodyVelFuseTime_ms
T x
Definition: vector3.h:67
bool useAirspeed(void) const
Vector3f receiverPos