APM:Libraries
AP_NavEKF2_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_NavEKF2.h"
6 #include "AP_NavEKF2_core.h"
7 #include <AP_AHRS/AP_AHRS.h>
9 #include <GCS_MAVLink/GCS.h>
10 
11 #include <stdio.h>
12 
13 extern const AP_HAL::HAL& hal;
14 
15 
16 // Control filter mode transitions
18 {
19  // Determine motor arm status
22  if (motorsArmed && !prevMotorsArmed) {
23  // set the time at which we arm to assist with checks
25  }
26 
27  // Detect if we are in flight on or ground
28  detectFlight();
29 
30  // Determine if learning of wind and magnetic field will be enabled and set corresponding indexing limits to
31  // avoid unnecessary operations
33 
34  // Check the alignmnent status of the tilt and yaw attitude
35  // Used during initial bootstrap alignment of the filter
37 
38  // Set the type of inertial navigation aiding used
39  setAidingMode();
40 
41 }
42 
43 /*
44  return effective value for _magCal for this core
45  */
46 uint8_t NavEKF2_core::effective_magCal(void) const
47 {
48  // force use of simple magnetic heading fusion for specified cores
49  if (frontend->_magMask & core_index) {
50  return 2;
51  } else {
52  return frontend->_magCal;
53  }
54 }
55 
56 // Determine if learning of wind and magnetic field will be enabled and set corresponding indexing limits to
57 // avoid unnecessary operations
59 {
60  // 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
61  bool setWindInhibit = (!useAirspeed() && !assume_zero_sideslip()) || onGround || (PV_AidingMode == AID_NONE);
62  if (!inhibitWindStates && setWindInhibit) {
63  inhibitWindStates = true;
64  } else if (inhibitWindStates && !setWindInhibit) {
65  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;
111  } else if (inhibitMagStates && !setMagInhibit) {
112  inhibitMagStates = false;
113  if (magFieldLearned) {
114  // if we have already learned the field states, then retain the learned variances
115  P[16][16] = earthMagFieldVar.x;
116  P[17][17] = earthMagFieldVar.y;
117  P[18][18] = earthMagFieldVar.z;
118  P[19][19] = bodyMagFieldVar.x;
119  P[20][20] = bodyMagFieldVar.y;
120  P[21][21] = bodyMagFieldVar.z;
121  } else {
122  // set the variances equal to the observation variances
123  for (uint8_t index=18; index<=21; index++) {
124  P[index][index] = sq(frontend->_magNoise);
125  }
126 
127  // set the NE earth magnetic field states using the published declination
128  // and set the corresponding variances and covariances
130 
131  }
132  // request a reset of the yaw and magnetic field states if not done before
134  magYawResetRequest = true;
135  }
136  }
137 
138  // If on ground we clear the flag indicating that the magnetic field in-flight initialisation has been completed
139  // because we want it re-done for each takeoff
140  if (onGround) {
141  finalInflightYawInit = false;
142  finalInflightMagInit = false;
143  }
144 
145  // Adjust the indexing limits used to address the covariance, states and other EKF arrays to avoid unnecessary operations
146  // if we are not using those states
148  stateIndexLim = 15;
149  } else if (inhibitWindStates) {
150  stateIndexLim = 21;
151  } else {
152  stateIndexLim = 23;
153  }
154 }
155 
156 // Set inertial navigation aiding mode
158 {
159  // Save the previous status so we can detect when it has changed
161 
162  // Determine if we should change aiding mode
163  switch (PV_AidingMode) {
164  case AID_NONE: {
165  // Don't allow filter to start position or velocity aiding until the tilt and yaw alignment is complete
166  // and IMU gyro bias estimates have stabilised
167  bool filterIsStable = tiltAlignComplete && yawAlignComplete && checkGyroCalStatus();
168  // If GPS usage has been prohiited then we use flow aiding provided optical flow data is present
169  // GPS aiding is the preferred option unless excluded by the user
170  bool canUseGPS = ((frontend->_fusionModeGPS) != 3 && readyToUseGPS() && filterIsStable && !gpsInhibit);
171  bool canUseRangeBeacon = readyToUseRangeBeacon() && filterIsStable;
172  bool canUseExtNav = readyToUseExtNav();
173  if(canUseGPS || canUseRangeBeacon || canUseExtNav) {
175  } else if (optFlowDataPresent() && filterIsStable) {
177  }
178  }
179  break;
180 
181  case AID_RELATIVE: {
182  // Check if the optical flow sensor has timed out
183  bool flowSensorTimeout = ((imuSampleTime_ms - flowValidMeaTime_ms) > 5000);
184  // Check if the fusion has timed out (flow measurements have been rejected for too long)
185  bool flowFusionTimeout = ((imuSampleTime_ms - prevFlowFuseTime_ms) > 5000);
186  // Enable switch to absolute position mode if GPS is available
187  // If GPS is not available and flow fusion has timed out, then fall-back to no-aiding
188  if((frontend->_fusionModeGPS) != 3 && readyToUseGPS() && !gpsInhibit) {
190  } else if (flowSensorTimeout || flowFusionTimeout) {
192  }
193  }
194  break;
195 
196  case AID_ABSOLUTE: {
197  // Find the minimum time without data required to trigger any check
199 
200  // Check if optical flow data is being used
201  bool optFlowUsed = (imuSampleTime_ms - prevFlowFuseTime_ms <= minTestTime_ms);
202 
203  // Check if airspeed data is being used
204  bool airSpdUsed = (imuSampleTime_ms - lastTasPassTime_ms <= minTestTime_ms);
205 
206  // Check if range beacon data is being used
207  bool rngBcnUsed = (imuSampleTime_ms - lastRngBcnPassTime_ms <= minTestTime_ms);
208 
209  // Check if GPS is being used
210  bool posUsed = (imuSampleTime_ms - lastPosPassTime_ms <= minTestTime_ms);
211  bool gpsVelUsed = (imuSampleTime_ms - lastVelPassTime_ms <= minTestTime_ms);
212 
213  // Check if attitude drift has been constrained by a measurement source
214  bool attAiding = posUsed || gpsVelUsed || optFlowUsed || airSpdUsed || rngBcnUsed;
215 
216  // check if velocity drift has been constrained by a measurement source
217  bool velAiding = gpsVelUsed || airSpdUsed || optFlowUsed;
218 
219  // check if position drift has been constrained by a measurement source
220  bool posAiding = posUsed || rngBcnUsed;
221 
222  // Check if the loss of attitude aiding has become critical
223  bool attAidLossCritical = false;
224  if (!attAiding) {
225  attAidLossCritical = (imuSampleTime_ms - prevFlowFuseTime_ms > frontend->tiltDriftTimeMax_ms) &&
226  (imuSampleTime_ms - lastTasPassTime_ms > frontend->tiltDriftTimeMax_ms) &&
227  (imuSampleTime_ms - lastRngBcnPassTime_ms > frontend->tiltDriftTimeMax_ms) &&
228  (imuSampleTime_ms - lastPosPassTime_ms > frontend->tiltDriftTimeMax_ms) &&
229  (imuSampleTime_ms - lastVelPassTime_ms > frontend->tiltDriftTimeMax_ms);
230  }
231 
232  // Check if the loss of position accuracy has become critical
233  bool posAidLossCritical = false;
234  if (!posAiding ) {
235  uint16_t maxLossTime_ms;
236  if (!velAiding) {
237  maxLossTime_ms = frontend->posRetryTimeNoVel_ms;
238  } else {
239  maxLossTime_ms = frontend->posRetryTimeUseVel_ms;
240  }
241  posAidLossCritical = (imuSampleTime_ms - lastRngBcnPassTime_ms > maxLossTime_ms) &&
242  (imuSampleTime_ms - lastPosPassTime_ms > maxLossTime_ms);
243  }
244 
245  if (attAidLossCritical) {
246  // if the loss of attitude data is critical, then put the filter into a constant position mode
248  posTimeout = true;
249  velTimeout = true;
250  rngBcnTimeout = true;
251  tasTimeout = true;
252  gpsNotAvailable = true;
253  } else if (posAidLossCritical) {
254  // if the loss of position is critical, declare all sources of position aiding as being timed out
255  posTimeout = true;
256  velTimeout = true;
257  rngBcnTimeout = true;
258  gpsNotAvailable = true;
259  }
260  }
261  break;
262 
263  default:
264  break;
265  }
266 
267  // check to see if we are starting or stopping aiding and set states and modes as required
269  // set various usage modes based on the condition when we start aiding. These are then held until aiding is stopped.
270  switch (PV_AidingMode) {
271  case AID_NONE:
272  // We have ceased aiding
273  gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u has stopped aiding",(unsigned)imu_index);
274  // When not aiding, estimate orientation & height fusing synthetic constant position and zero velocity measurement to constrain tilt errors
275  posTimeout = true;
276  velTimeout = true;
277  // Reset the normalised innovation to avoid false failing bad fusion tests
278  velTestRatio = 0.0f;
279  posTestRatio = 0.0f;
280  // store the current position to be used to keep reporting the last known position
283  // initialise filtered altitude used to provide a takeoff reference to current baro on disarm
284  // this reduces the time required for the baro noise filter to settle before the filtered baro data can be used
286  // reset the vertical position state to faster recover from baro errors experienced during touchdown
288  break;
289 
290  case AID_RELATIVE:
291  // We have commenced aiding, but GPS usage has been prohibited so use optical flow only
292  gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u is using optical flow",(unsigned)imu_index);
293  posTimeout = true;
294  velTimeout = true;
295  // Reset the last valid flow measurement time
297  // Reset the last valid flow fusion time
299  break;
300 
301  case AID_ABSOLUTE: {
302  bool canUseGPS = ((frontend->_fusionModeGPS) != 3 && readyToUseGPS() && !gpsInhibit);
303  bool canUseRangeBeacon = readyToUseRangeBeacon();
304  bool canUseExtNav = readyToUseExtNav();
305  // We have commenced aiding and GPS usage is allowed
306  if (canUseGPS) {
307  gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u is using GPS",(unsigned)imu_index);
308  }
309  posTimeout = false;
310  velTimeout = false;
311  // We have commenced aiding and range beacon usage is allowed
312  if (canUseRangeBeacon) {
313  gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u is using range beacons",(unsigned)imu_index);
314  gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u initial pos NE = %3.1f,%3.1f (m)",(unsigned)imu_index,(double)receiverPos.x,(double)receiverPos.y);
315  gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u initial beacon pos D offset = %3.1f (m)",(unsigned)imu_index,(double)bcnPosOffset);
316  }
317  // We have commenced aiding and external nav usage is allowed
318  if (canUseExtNav) {
319  gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u is using external nav data",(unsigned)imu_index);
320  gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u initial pos NED = %3.1f,%3.1f,%3.1f (m)",(unsigned)imu_index,(double)extNavDataDelayed.pos.x,(double)extNavDataDelayed.pos.y,(double)extNavDataDelayed.pos.z);
321  // handle yaw reset as special case
322  extNavYawResetRequest = true;
324  // handle height reset as special case
327  ResetHeight();
328  }
329  // reset the last fusion accepted times to prevent unwanted activation of timeout logic
333  }
334  break;
335 
336  default:
337  break;
338  }
339 
340  // Always reset the position and velocity when changing mode
341  ResetVelocity();
342  ResetPosition();
343  }
344 }
345 
346 // Check the tilt and yaw alignmnent status
347 // Used during initial bootstrap alignment of the filter
349 {
350  // Check for tilt convergence - used during initial alignment
351  float alpha = 1.0f*imuDataDelayed.delAngDT;
352  float temp=tiltErrVec.length();
353  tiltErrFilt = alpha*temp + (1.0f-alpha)*tiltErrFilt;
354  if (tiltErrFilt < 0.005f && !tiltAlignComplete) {
355  tiltAlignComplete = true;
356  gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u tilt alignment complete",(unsigned)imu_index);
357  }
358 
359  // submit yaw and magnetic field reset requests depending on whether we have compass data
361  if (use_compass()) {
362  magYawResetRequest = true;
363  gpsYawResetRequest = false;
364  } else {
365  magYawResetRequest = false;
366  gpsYawResetRequest = true;
367  }
368  }
369 }
370 
371 // return true if we should use the airspeed sensor
373 {
374  return _ahrs->airspeed_sensor_enabled();
375 }
376 
377 // return true if we should use the range finder sensor
379 {
380  // TO-DO add code to set this based in setting of optical flow use parameter and presence of sensor
381  return true;
382 }
383 
384 // return true if optical flow data is available
386 {
387  return (imuSampleTime_ms - flowMeaTime_ms < 200);
388 }
389 
390 // return true if the filter to be ready to use gps
392 {
394 }
395 
396 // return true if the filter to be ready to use the beacon range measurements
398 {
400 }
401 
402 // return true if the filter to be ready to use external nav data
404 {
406 }
407 
408 // return true if we should use the compass
410 {
412 }
413 
414 /*
415  should we assume zero sideslip?
416  */
418 {
419  // we don't assume zero sideslip for ground vehicles as EKF could
420  // be quite sensitive to a rapid spin of the ground vehicle if
421  // traction is lost
423 }
424 
425 // set the LLH location of the filters NED origin
427 {
429  return false;
430  }
431  EKF_origin = loc;
432  ekfGpsRefHgt = (double)0.01 * (double)EKF_origin.alt;
433  // define Earth rotation vector in the NED navigation frame at the origin
435  validOrigin = true;
436  return true;
437 }
438 
439 // Set the NED origin to be used until the next filter reset
441 {
442  // assume origin at current GPS location (no averaging)
444  // if flying, correct for height change from takeoff so that the origin is at field elevation
445  if (inFlight) {
446  EKF_origin.alt += (int32_t)(100.0f * stateStruct.position.z);
447  }
448  ekfGpsRefHgt = (double)0.01 * (double)EKF_origin.alt;
449  // define Earth rotation vector in the NED navigation frame at the origin
451  validOrigin = true;
452  gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u Origin set to GPS",(unsigned)imu_index);
453 }
454 
455 // record a yaw reset event
457 {
458  yawAlignComplete = true;
459  if (inFlight) {
460  finalInflightYawInit = true;
461  }
462 }
463 
464 // return true and set the class variable true if the delta angle bias has been learned
466 {
467  // check delta angle bias variances
468  const float delAngBiasVarMax = sq(radians(0.15f * dtEkfAvg));
469  delAngBiasLearned = (P[9][9] <= delAngBiasVarMax) &&
470  (P[10][10] <= delAngBiasVarMax) &&
471  (P[11][11] <= delAngBiasVarMax);
472  return delAngBiasLearned;
473 }
474 
475 // Commands the EKF to not use GPS.
476 // This command must be sent prior to arming
477 // This command is forgotten by the EKF each time the vehicle disarms
478 // Returns 0 if command rejected
479 // Returns 1 if attitude, vertical velocity and vertical position will be provided
480 // Returns 2 if attitude, 3D-velocity, vertical position and relative horizontal position will be provided
482 {
484  return 0;
485  } else {
486  gpsInhibit = true;
487  return 1;
488  }
489  // option 2 is not yet implemented as it requires a deeper integration of optical flow and GPS operation
490 }
491 
492 // Update the filter status
494 {
495  // init return value
496  filterStatus.value = 0;
497  bool doingFlowNav = (PV_AidingMode == AID_RELATIVE) && flowDataValid;
498  bool doingWindRelNav = !tasTimeout && assume_zero_sideslip();
499  bool doingNormalGpsNav = !posTimeout && (PV_AidingMode == AID_ABSOLUTE);
500  bool someVertRefData = (!velTimeout && useGpsVertVel) || !hgtTimeout;
501  bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav;
502  bool optFlowNavPossible = flowDataValid && delAngBiasLearned;
503  bool gpsNavPossible = !gpsNotAvailable && gpsGoodToAlign && delAngBiasLearned;
504  bool filterHealthy = healthy() && tiltAlignComplete && (yawAlignComplete || (!use_compass() && (PV_AidingMode == AID_NONE)));
505  // If GPS height usage is specified, height is considered to be inaccurate until the GPS passes all checks
506  bool hgtNotAccurate = (frontend->_altSource == 2) && !validOrigin;
507 
508  // set individual flags
509  filterStatus.flags.attitude = !stateStruct.quat.is_nan() && filterHealthy; // attitude valid (we need a better check)
510  filterStatus.flags.horiz_vel = someHorizRefData && filterHealthy; // horizontal velocity estimate valid
511  filterStatus.flags.vert_vel = someVertRefData && filterHealthy; // vertical velocity estimate valid
512  filterStatus.flags.horiz_pos_rel = ((doingFlowNav && gndOffsetValid) || doingWindRelNav || doingNormalGpsNav) && filterHealthy; // relative horizontal position estimate valid
513  filterStatus.flags.horiz_pos_abs = doingNormalGpsNav && filterHealthy; // absolute horizontal position estimate valid
514  filterStatus.flags.vert_pos = !hgtTimeout && filterHealthy && !hgtNotAccurate; // vertical position estimate valid
515  filterStatus.flags.terrain_alt = gndOffsetValid && filterHealthy; // terrain height estimate valid
516  filterStatus.flags.const_pos_mode = (PV_AidingMode == AID_NONE) && filterHealthy; // constant position mode
517  filterStatus.flags.pred_horiz_pos_rel = ((optFlowNavPossible || gpsNavPossible) && filterHealthy) || filterStatus.flags.horiz_pos_rel; // we should be able to estimate a relative position when we enter flight mode
518  filterStatus.flags.pred_horiz_pos_abs = (gpsNavPossible && filterHealthy) || filterStatus.flags.horiz_pos_abs; // we should be able to estimate an absolute position when we enter flight mode
519  filterStatus.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected
520  filterStatus.flags.takeoff = expectGndEffectTakeoff; // The EKF has been told to expect takeoff and is in a ground effect mitigation mode
521  filterStatus.flags.touchdown = expectGndEffectTouchdown; // The EKF has been told to detect touchdown and is in a ground effect mitigation mode
522  filterStatus.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE);
523  filterStatus.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE) && !extNavUsedForPos; // GPS glitching is affecting navigation accuracy
524 }
525 
526 #endif // HAL_CPU_CLASS
void to_euler(float &roll, float &pitch, float &yaw) const
Definition: quaternion.cpp:272
Vector3f tiltErrVec
uint32_t lastVelPassTime_ms
bool get_soft_armed() const
Definition: Util.h:15
uint8_t effective_magCal(void) const
AP_Int8 _magCal
Definition: AP_NavEKF2.h:373
Vector3f earthRateNED
AP_Int8 _fusionModeGPS
Definition: AP_NavEKF2.h:367
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
AP_Float _magNoise
Definition: AP_NavEKF2.h:355
bool extNavYawResetRequest
AP_Float _easNoise
Definition: AP_NavEKF2.h:356
NavEKF2 * frontend
Interface definition for the various Ground Control System.
bool assume_zero_sideslip(void) const
AP_Int8 _altSource
Definition: AP_NavEKF2.h:380
const uint16_t posRetryTimeNoVel_ms
Definition: AP_NavEKF2.h:408
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
const AP_AHRS * _ahrs
bool healthy(void) const
AHRS_VehicleClass get_vehicle_class(void) const
Definition: AP_AHRS.h:133
AP_HAL::Util * util
Definition: HAL.h:115
uint8_t core_index
GCS & gcs()
void updateFilterStatus(void)
const Location & location(uint8_t instance) const
Definition: AP_GPS.h:200
Vector3f bodyMagFieldVar
const uint16_t posRetryTimeUseVel_ms
Definition: AP_NavEKF2.h:407
struct NavEKF2_core::state_elements & stateStruct
uint32_t imuSampleTime_ms
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
#define MIN(a, b)
Definition: usb_conf.h:215
const Compass * get_compass() const
Definition: AP_AHRS.h:150
imu_elements imuDataDelayed
uint8_t setInhibitGPS(void)
Vector3f earthMagFieldVar
T y
Definition: vector2.h:37
bool readyToUseGPS(void) const
bool readyToUseRangeBeacon(void) const
baro_elements baroDataDelayed
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
AP_Int8 _magMask
Definition: AP_NavEKF2.h:397
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
bool optFlowDataPresent(void) const
uint8_t magSelectIndex
bool readyToUseExtNav(void) const
#define f(i)
uint32_t prevFlowFuseTime_ms
const uint16_t tiltDriftTimeMax_ms
Definition: AP_NavEKF2.h:406
T y
Definition: vector3.h:67
bool useAirspeed(void) const
T z
Definition: vector3.h:67
void setWindMagStateLearningMode()
AidingMode PV_AidingModePrev
bool useRngFinder(void) const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
bool use_compass(void) const
float length(void) const
Definition: vector3.cpp:288
bool magStateInitComplete
struct nav_filter_status::@138 flags
void calcEarthRateNED(Vector3f &omega, int32_t latitude) const
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
uint32_t timeAtArming_ms
struct Location EKF_origin
nav_filter_status filterStatus
bool setOriginLLH(const Location &loc)
ext_nav_elements extNavDataDelayed
uint32_t lastRngBcnPassTime_ms
static constexpr float radians(float deg)
Definition: AP_Math.h:158
uint32_t flowMeaTime_ms
uint8_t stateIndexLim
bool get_fly_forward(void) const
Definition: AP_AHRS.h:97
float sq(const T val)
Definition: AP_Math.h:170
bool expectGndEffectTouchdown
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
bool is_nan(void) const
Definition: quaternion.h:59
bool expectGndEffectTakeoff
uint32_t lastPosPassTime_ms
uint32_t lastTasPassTime_ms
tas_elements tasDataDelayed
void checkAttitudeAlignmentStatus()
uint32_t flowValidMeaTime_ms
Vector3f receiverPos
Vector2f lastKnownPositionNE
bool checkGyroCalStatus(void)
bool allMagSensorsFailed
AidingMode PV_AidingMode
T x
Definition: vector3.h:67