APM:Libraries
AP_NavEKF3_Outputs.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 
10 extern const AP_HAL::HAL& hal;
11 
12 
13 // Check basic filter health metrics and return a consolidated health status
14 bool NavEKF3_core::healthy(void) const
15 {
16  uint16_t faultInt;
17  getFilterFaults(faultInt);
18  if (faultInt > 0) {
19  return false;
20  }
21  if (velTestRatio > 1 && posTestRatio > 1 && hgtTestRatio > 1) {
22  // all three metrics being above 1 means the filter is
23  // extremely unhealthy.
24  return false;
25  }
26  // Give the filter a second to settle before use
27  if ((imuSampleTime_ms - ekfStartTime_ms) < 1000 ) {
28  return false;
29  }
30  // position and height innovations must be within limits when on-ground and in a static mode of operation
31  float horizErrSq = sq(innovVelPos[3]) + sq(innovVelPos[4]);
32  if (onGround && (PV_AidingMode == AID_NONE) && ((horizErrSq > 1.0f) || (fabsf(hgtInnovFiltState) > 1.0f))) {
33  return false;
34  }
35 
36  // all OK
37  return true;
38 }
39 
40 // Return a consolidated error score where higher numbers represent larger errors
41 // Intended to be used by the front-end to determine which is the primary EKF
43 {
44  float score = 0.0f;
46  // Check GPS fusion performance
47  score = MAX(score, 0.5f * (velTestRatio + posTestRatio));
48  // Check altimeter fusion performance
49  score = MAX(score, hgtTestRatio);
50  }
51  return score;
52 }
53 
54 // return data for debugging optical flow fusion
55 void NavEKF3_core::getFlowDebug(float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
56 {
57  varFlow = MAX(flowTestRatio[0],flowTestRatio[1]);
58  gndOffset = terrainState;
59  flowInnovX = innovOptFlow[0];
60  flowInnovY = innovOptFlow[1];
61  auxInnov = auxFlowObsInnov;
63  rngInnov = innovRng;
64  range = rangeDataDelayed.rng;
65  gndOffsetErr = sqrtf(Popt); // note Popt is constrained to be non-negative in EstimateTerrainOffset()
66 }
67 
68 // return data for debugging body frame odometry fusion
69 uint32_t NavEKF3_core::getBodyFrameOdomDebug(Vector3f &velInnov, Vector3f &velInnovVar)
70 {
71  velInnov.x = innovBodyVel[0];
72  velInnov.y = innovBodyVel[1];
73  velInnov.z = innovBodyVel[2];
74  velInnovVar.x = varInnovBodyVel[0];
75  velInnovVar.y = varInnovBodyVel[1];
76  velInnovVar.z = varInnovBodyVel[2];
78 }
79 
80 // return data for debugging range beacon fusion one beacon at a time, incrementing the beacon index after each call
81 bool NavEKF3_core::getRangeBeaconDebug(uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED,
82  float &offsetHigh, float &offsetLow, Vector3f &posNED)
83 {
84  // if the states have not been initialised or we have not received any beacon updates then return zeros
85  if (!statesInitialised || N_beacons == 0) {
86  return false;
87  }
88 
89  // Ensure that beacons are not skipped due to calling this function at a rate lower than the updates
92  }
93 
94  // Output the fusion status data for the specified beacon
95  ID = rngBcnFuseDataReportIndex; // beacon identifier
96  rng = rngBcnFusionReport[rngBcnFuseDataReportIndex].rng; // measured range to beacon (m)
97  innov = rngBcnFusionReport[rngBcnFuseDataReportIndex].innov; // range innovation (m)
98  innovVar = rngBcnFusionReport[rngBcnFuseDataReportIndex].innovVar; // innovation variance (m^2)
99  testRatio = rngBcnFusionReport[rngBcnFuseDataReportIndex].testRatio; // innovation consistency test ratio
100  beaconPosNED = rngBcnFusionReport[rngBcnFuseDataReportIndex].beaconPosNED; // beacon receiver NED position (m)
101  offsetHigh = bcnPosDownOffsetMax; // beacon system vertical pos offset upper estimate (m)
102  offsetLow = bcnPosDownOffsetMin; // beacon system vertical pos offset lower estimate (m)
103  posNED = receiverPos; // beacon system NED offset (m)
105  return true;
106 }
107 
108 // provides the height limit to be observed by the control loops
109 // returns false if no height limiting is required
110 // this is needed to ensure the vehicle does not fly too high when using optical flow navigation
111 bool NavEKF3_core::getHeightControlLimit(float &height) const
112 {
113  // only ask for limiting if we are doing optical flow navigation
114  if (frontend->_fusionModeGPS == 3) {
115  // If are doing optical flow nav, ensure the height above ground is within range finder limits after accounting for vehicle tilt and control errors
116  height = MAX(float(frontend->_rng.max_distance_cm_orient(ROTATION_PITCH_270)) * 0.007f - 1.0f, 1.0f);
117  // If we are are not using the range finder as the height reference, then compensate for the difference between terrain and EKF origin
118  if (frontend->_altSource != 1) {
119  height -= terrainState;
120  }
121  return true;
122  } else {
123  return false;
124  }
125 }
126 
127 
128 // return the Euler roll, pitch and yaw angle in radians
130 {
131  outputDataNew.quat.to_euler(euler.x, euler.y, euler.z);
132  euler = euler - _ahrs->get_trim();
133 }
134 
135 // return body axis gyro bias estimates in rad/sec
136 void NavEKF3_core::getGyroBias(Vector3f &gyroBias) const
137 {
138  if (dtEkfAvg < 1e-6f) {
139  gyroBias.zero();
140  return;
141  }
142  gyroBias = stateStruct.gyro_bias / dtEkfAvg;
143 }
144 
145 // return accelerometer bias in m/s/s
146 void NavEKF3_core::getAccelBias(Vector3f &accelBias) const
147 {
148  if (!statesInitialised) {
149  accelBias.zero();
150  return;
151  }
152  accelBias = stateStruct.accel_bias / dtEkfAvg;
153 }
154 
155 // return tilt error convergence metric
156 void NavEKF3_core::getTiltError(float &ang) const
157 {
158  ang = stateStruct.quat.length();
159 }
160 
161 // return the transformation matrix from XYZ (body) to NED axes
163 {
166 }
167 
168 // return the quaternions defining the rotation from NED to XYZ (body) axes
170 {
171  ret = outputDataNew.quat;
172 }
173 
174 // return the amount of yaw angle change due to the last yaw angle reset in radians
175 // returns the time of the last yaw angle reset or 0 if no reset has ever occurred
176 uint32_t NavEKF3_core::getLastYawResetAngle(float &yawAng) const
177 {
178  yawAng = yawResetAngle;
179  return lastYawReset_ms;
180 }
181 
182 // return the amount of NE position change due to the last position reset in metres
183 // returns the time of the last reset or 0 if no reset has ever occurred
185 {
186  pos = posResetNE;
187  return lastPosReset_ms;
188 }
189 
190 // return the amount of vertical position change due to the last vertical position reset in metres
191 // returns the time of the last reset or 0 if no reset has ever occurred
192 uint32_t NavEKF3_core::getLastPosDownReset(float &posD) const
193 {
194  posD = posResetD;
195  return lastPosResetD_ms;
196 }
197 
198 // return the amount of NE velocity change due to the last velocity reset in metres/sec
199 // returns the time of the last reset or 0 if no reset has ever occurred
201 {
202  vel = velResetNE;
203  return lastVelReset_ms;
204 }
205 
206 // return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis)
208 {
209  wind.x = stateStruct.wind_vel.x;
210  wind.y = stateStruct.wind_vel.y;
211  wind.z = 0.0f; // currently don't estimate this
212 }
213 
214 
215 // return the NED velocity of the body frame origin in m/s
216 //
218 {
219  // correct for the IMU position offset (EKF calculations are at the IMU)
221 }
222 
223 // Return the rate of change of vertical position in the down diection (dPosD/dt) of the body frame origin in m/s
225 {
226  // return the value calculated from a complementary filter applied to the EKF height and vertical acceleration
227  // correct for the IMU offset (EKF calculations are at the IMU)
229 }
230 
231 // This returns the specific forces in the NED frame
232 void NavEKF3_core::getAccelNED(Vector3f &accelNED) const {
233  accelNED = velDotNED;
234  accelNED.z -= GRAVITY_MSS;
235 }
236 
237 // Write the last estimated NE position of the body frame origin relative to the reference point (m).
238 // Return true if the estimate is valid
240 {
241  // There are three modes of operation, absolute position (GPS fusion), relative position (optical flow fusion) and constant position (no position estimate available)
242  if (PV_AidingMode != AID_NONE) {
243  // This is the normal mode of operation where we can use the EKF position states
244  // correct for the IMU offset (EKF calculations are at the IMU)
247  return true;
248 
249  } else {
250  // In constant position mode the EKF position states are at the origin, so we cannot use them as a position estimate
251  if(validOrigin) {
252  if ((AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D)) {
253  // If the origin has been set and we have GPS, then return the GPS position relative to the origin
254  const struct Location &gpsloc = AP::gps().location();
255  Vector2f tempPosNE = location_diff(EKF_origin, gpsloc);
256  posNE.x = tempPosNE.x;
257  posNE.y = tempPosNE.y;
258  return false;
259  } else if (rngBcnAlignmentStarted) {
260  // If we are attempting alignment using range beacon data, then report the position
261  posNE.x = receiverPos.x;
262  posNE.y = receiverPos.y;
263  return false;
264  } else {
265  // If no GPS fix is available, all we can do is provide the last known position
266  posNE.x = outputDataNew.position.x;
267  posNE.y = outputDataNew.position.y;
268  return false;
269  }
270  } else {
271  // If the origin has not been set, then we have no means of providing a relative position
272  posNE.x = 0.0f;
273  posNE.y = 0.0f;
274  return false;
275  }
276  }
277  return false;
278 }
279 
280 // Write the last calculated D position of the body frame origin relative to the EKF origin (m).
281 // Return true if the estimate is valid
282 bool NavEKF3_core::getPosD(float &posD) const
283 {
284  // The EKF always has a height estimate regardless of mode of operation
285  // Correct for the IMU offset (EKF calculations are at the IMU)
286  // Also correct for changes to the origin height
287  if ((frontend->_originHgtMode & (1<<2)) == 0) {
288  // Any sensor height drift corrections relative to the WGS-84 reference are applied to the origin.
290  } else {
291  // The origin height is static and corrections are applied to the local vertical position
292  // so that height returned by getLLH() = height returned by getOriginLLH - posD
293  posD = outputDataNew.position.z + posOffsetNED.z + 0.01f * (float)EKF_origin.alt - (float)ekfGpsRefHgt;
294  }
295 
296  // Return the current height solution status
297  return filterStatus.flags.vert_pos;
298 
299 }
300 
301 // return the estimated height of body frame origin above ground level
302 bool NavEKF3_core::getHAGL(float &HAGL) const
303 {
305  // If we know the terrain offset and altitude, then we have a valid height above ground estimate
306  return !hgtTimeout && gndOffsetValid && healthy();
307 }
308 
309 // Return the last calculated latitude, longitude and height in WGS-84
310 // If a calculated location isn't available, return a raw GPS measurement
311 // The status will return true if a calculation or raw measurement is available
312 // The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control
313 bool NavEKF3_core::getLLH(struct Location &loc) const
314 {
315  const AP_GPS &gps = AP::gps();
316 
317  if(validOrigin) {
318  // Altitude returned is an absolute altitude relative to the WGS-84 spherioid
319  loc.alt = 100 * (int32_t)(ekfGpsRefHgt - (double)outputDataNew.position.z);
320  loc.flags.relative_alt = 0;
321  loc.flags.terrain_alt = 0;
322 
323  // there are three modes of operation, absolute position (GPS fusion), relative position (optical flow fusion) and constant position (no aiding)
325  loc.lat = EKF_origin.lat;
326  loc.lng = EKF_origin.lng;
328  return true;
329  } else {
330  // we could be in constant position mode because the vehicle has taken off without GPS, or has lost GPS
331  // in this mode we cannot use the EKF states to estimate position so will return the best available data
332  if ((gps.status() >= AP_GPS::GPS_OK_FIX_2D)) {
333  // we have a GPS position fix to return
334  const struct Location &gpsloc = gps.location();
335  loc.lat = gpsloc.lat;
336  loc.lng = gpsloc.lng;
337  return true;
338  } else {
339  // if no GPS fix, provide last known position before entering the mode
341  return false;
342  }
343  }
344  } else {
345  // If no origin has been defined for the EKF, then we cannot use its position states so return a raw
346  // GPS reading if available and return false
347  if ((gps.status() >= AP_GPS::GPS_OK_FIX_3D)) {
348  const struct Location &gpsloc = gps.location();
349  loc = gpsloc;
350  loc.flags.relative_alt = 0;
351  loc.flags.terrain_alt = 0;
352  }
353  return false;
354  }
355 }
356 
357 
358 // return the horizontal speed limit in m/s set by optical flow sensor limits
359 // return the scale factor to be applied to navigation velocity gains to compensate for increase in velocity noise with height when using optical flow
360 void NavEKF3_core::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
361 {
362  // If in the last 10 seconds we have received flow data and no odometry data, then we are relying on optical flow
363  bool relyingOnFlowData = (imuSampleTime_ms - prevBodyVelFuseTime_ms > 1000)
364  && (imuSampleTime_ms - flowValidMeaTime_ms <= 10000);
365 
366  // If relying on optical flow, limit speed to prevent sensor limit being exceeded and adjust
367  // nav gains to prevent body rate feedback into flow rates destabilising the control loop
368  if (PV_AidingMode == AID_RELATIVE && relyingOnFlowData) {
369  // allow 1.0 rad/sec margin for angular motion
370  ekfGndSpdLimit = MAX((frontend->_maxFlowRate - 1.0f), 0.0f) * MAX((terrainState - stateStruct.position[2]), rngOnGnd);
371  // use standard gains up to 5.0 metres height and reduce above that
372  ekfNavVelGainScaler = 4.0f / MAX((terrainState - stateStruct.position[2]),4.0f);
373  } else {
374  ekfGndSpdLimit = 400.0f; //return 80% of max filter speed
375  ekfNavVelGainScaler = 1.0f;
376  }
377 }
378 
379 
380 // return the LLH location of the filters NED origin
381 bool NavEKF3_core::getOriginLLH(struct Location &loc) const
382 {
383  if (validOrigin) {
384  loc = EKF_origin;
385  // report internally corrected reference height if enabled
386  if ((frontend->_originHgtMode & (1<<2)) == 0) {
387  loc.alt = (int32_t)(100.0f * (float)ekfGpsRefHgt);
388  }
389  }
390  return validOrigin;
391 }
392 
393 // return earth magnetic field estimates in measurement units / 1000
395 {
396  magNED = stateStruct.earth_magfield * 1000.0f;
397 }
398 
399 // return body magnetic field estimates in measurement units / 1000
401 {
402  magXYZ = stateStruct.body_magfield*1000.0f;
403 }
404 
405 // return magnetometer offsets
406 // return true if offsets are valid
407 bool NavEKF3_core::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
408 {
409  if (!_ahrs->get_compass()) {
410  return false;
411  }
412  // compass offsets are valid if we have finalised magnetic field initialisation, magnetic field learning is not prohibited,
413  // primary compass is valid and state variances have converged
414  const float maxMagVar = 5E-6f;
415  bool variancesConverged = (P[19][19] < maxMagVar) && (P[20][20] < maxMagVar) && (P[21][21] < maxMagVar);
416  if ((mag_idx == magSelectIndex) &&
418  !inhibitMagStates &&
420  variancesConverged) {
422  return true;
423  } else {
424  magOffsets = _ahrs->get_compass()->get_offsets(magSelectIndex);
425  return false;
426  }
427 }
428 
429 // return the index for the active magnetometer
431 {
432  return (uint8_t)magSelectIndex;
433 }
434 
435 // return the innovations for the NED Pos, NED Vel, XYZ Mag and Vtas measurements
436 void NavEKF3_core::getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
437 {
438  velInnov.x = innovVelPos[0];
439  velInnov.y = innovVelPos[1];
440  velInnov.z = innovVelPos[2];
441  posInnov.x = innovVelPos[3];
442  posInnov.y = innovVelPos[4];
443  posInnov.z = innovVelPos[5];
444  magInnov.x = 1e3f*innovMag[0]; // Convert back to sensor units
445  magInnov.y = 1e3f*innovMag[1]; // Convert back to sensor units
446  magInnov.z = 1e3f*innovMag[2]; // Convert back to sensor units
447  tasInnov = innovVtas;
448  yawInnov = innovYaw;
449 }
450 
451 // return the innovation consistency test ratios for the velocity, position, magnetometer and true airspeed measurements
452 // this indicates the amount of margin available when tuning the various error traps
453 // also return the delta in position due to the last position reset
454 void NavEKF3_core::getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
455 {
456  velVar = sqrtf(velTestRatio);
457  posVar = sqrtf(posTestRatio);
458  hgtVar = sqrtf(hgtTestRatio);
459  // If we are using simple compass yaw fusion, populate all three components with the yaw test ratio to provide an equivalent output
460  magVar.x = sqrtf(MAX(magTestRatio.x,yawTestRatio));
461  magVar.y = sqrtf(MAX(magTestRatio.y,yawTestRatio));
462  magVar.z = sqrtf(MAX(magTestRatio.z,yawTestRatio));
463  tasVar = sqrtf(tasTestRatio);
464  offset = posResetNE;
465 }
466 
467 // return the diagonals from the covariance matrix
468 void NavEKF3_core::getStateVariances(float stateVar[24])
469 {
470  for (uint8_t i=0; i<24; i++) {
471  stateVar[i] = P[i][i];
472  }
473 }
474 
475 /*
476 return the filter fault status as a bitmasked integer
477  0 = quaternions are NaN
478  1 = velocities are NaN
479  2 = badly conditioned X magnetometer fusion
480  3 = badly conditioned Y magnetometer fusion
481  5 = badly conditioned Z magnetometer fusion
482  6 = badly conditioned airspeed fusion
483  7 = badly conditioned synthetic sideslip fusion
484  7 = filter is not initialised
485 */
486 void NavEKF3_core::getFilterFaults(uint16_t &faults) const
487 {
488  faults = (stateStruct.quat.is_nan()<<0 |
490  faultStatus.bad_xmag<<2 |
491  faultStatus.bad_ymag<<3 |
492  faultStatus.bad_zmag<<4 |
493  faultStatus.bad_airspeed<<5 |
494  faultStatus.bad_sideslip<<6 |
495  !statesInitialised<<7);
496 }
497 
498 /*
499 return filter timeout status as a bitmasked integer
500  0 = position measurement timeout
501  1 = velocity measurement timeout
502  2 = height measurement timeout
503  3 = magnetometer measurement timeout
504  4 = true airspeed measurement timeout
505  5 = unassigned
506  6 = unassigned
507  7 = unassigned
508 */
509 void NavEKF3_core::getFilterTimeouts(uint8_t &timeouts) const
510 {
511  timeouts = (posTimeout<<0 |
512  velTimeout<<1 |
513  hgtTimeout<<2 |
514  magTimeout<<3 |
515  tasTimeout<<4);
516 }
517 
518 // Return the navigation filter status message
520 {
521  status = filterStatus;
522 }
523 
524 /*
525 return filter gps quality check status
526 */
528 {
529  // init return value
530  faults.value = 0;
531 
532  // set individual flags
533  faults.flags.bad_sAcc = gpsCheckStatus.bad_sAcc; // reported speed accuracy is insufficient
534  faults.flags.bad_hAcc = gpsCheckStatus.bad_hAcc; // reported horizontal position accuracy is insufficient
535  faults.flags.bad_vAcc = gpsCheckStatus.bad_vAcc; // reported vertical position accuracy is insufficient
536  faults.flags.bad_yaw = gpsCheckStatus.bad_yaw; // EKF heading accuracy is too large for GPS use
537  faults.flags.bad_sats = gpsCheckStatus.bad_sats; // reported number of satellites is insufficient
538  faults.flags.bad_horiz_drift = gpsCheckStatus.bad_horiz_drift; // GPS horizontal drift is too large to start using GPS (check assumes vehicle is static)
539  faults.flags.bad_hdop = gpsCheckStatus.bad_hdop; // reported HDoP is too large to start using GPS
540  faults.flags.bad_vert_vel = gpsCheckStatus.bad_vert_vel; // GPS vertical speed is too large to start using GPS (check assumes vehicle is static)
541  faults.flags.bad_fix = gpsCheckStatus.bad_fix; // The GPS cannot provide the 3D fix required
542  faults.flags.bad_horiz_vel = gpsCheckStatus.bad_horiz_vel; // The GPS horizontal speed is excessive (check assumes the vehicle is static)
543 }
544 
545 // send an EKF_STATUS message to GCS
546 void NavEKF3_core::send_status_report(mavlink_channel_t chan)
547 {
548  // prepare flags
549  uint16_t flags = 0;
551  flags |= EKF_ATTITUDE;
552  }
554  flags |= EKF_VELOCITY_HORIZ;
555  }
557  flags |= EKF_VELOCITY_VERT;
558  }
560  flags |= EKF_POS_HORIZ_REL;
561  }
563  flags |= EKF_POS_HORIZ_ABS;
564  }
566  flags |= EKF_POS_VERT_ABS;
567  }
569  flags |= EKF_POS_VERT_AGL;
570  }
572  flags |= EKF_CONST_POS_MODE;
573  }
575  flags |= EKF_PRED_POS_HORIZ_REL;
576  }
578  flags |= EKF_PRED_POS_HORIZ_ABS;
579  }
581  flags |= (1<<15);
582  }
583 
584  // get variances
585  float velVar, posVar, hgtVar, tasVar;
586  Vector3f magVar;
587  Vector2f offset;
588  getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
589 
590  // Only report range finder normalised innovation levels if the EKF needs the data for primary
591  // height estimation or optical flow operation. This prevents false alarms at the GCS if a
592  // range finder is fitted for other applications
593  float temp;
595  temp = sqrtf(auxRngTestRatio);
596  } else {
597  temp = 0.0f;
598  }
599 
600  // send message
601  mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.length(), temp, tasVar);
602 
603 }
604 
605 // report the reason for why the backend is refusing to initialise
606 const char *NavEKF3_core::prearm_failure_reason(void) const
607 {
608  if (imuSampleTime_ms - lastGpsVelFail_ms > 10000) {
609  // we are not failing
610  return nullptr;
611  }
612  return prearm_fail_string;
613 }
614 
615 
616 // report the number of frames lapsed since the last state prediction
617 // this is used by other instances to level load
619 {
620  return framesSincePredict;
621 }
622 
623 // publish output observer angular, velocity and position tracking error
625 {
626  error = outputTrackError;
627 }
628 
629 #endif // HAL_CPU_CLASS
uint8_t magSelectIndex
void to_euler(float &roll, float &pitch, float &yaw) const
Definition: quaternion.cpp:272
struct nav_gps_status::@139 flags
Definition: AP_GPS.h:48
void getRotationBodyToNED(Matrix3f &mat) const
char prearm_fail_string[40]
uint8_t activeHgtSource
AP_Int8 _originHgtMode
Definition: AP_NavEKF3.h:415
const Vector3f & get_trim() const
Definition: AP_AHRS.h:385
float getPosDownDerivative(void) const
AP_Int8 _fusionModeGPS
Definition: AP_NavEKF3.h:384
void getFilterFaults(uint16_t &faults) const
bool getPosD(float &posD) const
bool getPosNE(Vector2f &posNE) const
uint32_t getBodyFrameOdomDebug(Vector3f &velInnov, Vector3f &velInnovVar)
uint8_t getActiveMag() const
Vector2 flowTestRatio
void getVelNED(Vector3f &vel) const
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
void getAccelBias(Vector3f &accelBias) const
vel_odm_elements bodyOdmDataDelayed
const AP_AHRS * _ahrs
void getMagNED(Vector3f &magNED) const
const RangeFinder & _rng
Definition: AP_NavEKF3.h:362
bool is_nan(void) const
Definition: vector3.cpp:315
bool rngBcnAlignmentStarted
void getQuaternion(Quaternion &quat) const
uint32_t lastPosReset_ms
void getTiltError(float &ang) const
Vector2 innovOptFlow
uint32_t lastPosResetD_ms
#define HGT_SOURCE_RNG
void getGyroBias(Vector3f &gyroBias) const
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
Definition: location.cpp:125
AidingMode PV_AidingMode
const Location & location(uint8_t instance) const
Definition: AP_GPS.h:200
void getFilterStatus(nav_filter_status &status) const
struct NavEKF3_core::@153 faultStatus
Vector3f velOffsetNED
uint32_t flowValidMeaTime_ms
uint32_t framesSincePredict
wheel_odm_elements wheelOdmDataDelayed
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
uint32_t lastYawReset_ms
AP_Int8 _altSource
Definition: AP_NavEKF3.h:397
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
range_elements rangeDataDelayed
struct NavEKF3_core::state_elements & stateStruct
Vector3 innovBodyVel
const Compass * get_compass() const
Definition: AP_AHRS.h:150
float errorScore(void) const
uint32_t getLastYawResetAngle(float &yawAng) const
T y
Definition: vector2.h:37
float posDownDerivative
void getWind(Vector3f &wind) const
Vector3f posOffsetNED
AP_Float _maxFlowRate
Definition: AP_NavEKF3.h:396
bool getRangeBeaconDebug(uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow, Vector3f &posNED)
output_elements outputDataNew
bool getHAGL(float &HAGL) const
float bcnPosDownOffsetMax
uint32_t getLastPosNorthEastReset(Vector2f &pos) const
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
uint16_t value
Definition: AP_Nav_Common.h:56
Vector2f lastKnownPositionNE
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
#define GRAVITY_MSS
Definition: definitions.h:47
void getEulerAngles(Vector3f &eulers) const
#define f(i)
Vector3f outputTrackError
T y
Definition: vector3.h:67
void getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
const Vector3f & get_offsets(uint8_t i) const
Definition: AP_Compass.h:166
uint32_t ekfStartTime_ms
const Matrix3f & get_rotation_vehicle_body_to_autopilot_body(void) const
Definition: AP_AHRS.h:264
T z
Definition: vector3.h:67
uint8_t rngBcnFuseDataReportIndex
Vector2f velResetNE
int16_t max_distance_cm_orient(enum Rotation orientation) const
Vector3f velDotNED
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
bool healthy[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:301
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
uint32_t getLastPosDownReset(float &posD) const
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
void getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
struct NavEKF3_core::@152 rngBcnFusionReport[10]
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
void getFilterGpsStatus(nav_gps_status &status) const
float length(void) const
Definition: vector3.cpp:288
struct nav_filter_status::@138 flags
void getFlowDebug(float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
struct NavEKF3_core::@154 gpsCheckStatus
T x
Definition: vector2.h:37
Vector3f magTestRatio
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
Vector3f innovMag
bool healthy(void) const
Vector6 innovVelPos
void getStateVariances(float stateVar[24])
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void getOutputTrackingError(Vector3f &error) const
Vector2f posResetNE
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
uint8_t getFramesSincePredict(void) const
#define error(fmt, args ...)
float sq(const T val)
Definition: AP_Math.h:170
const char * prearm_failure_reason(void) const
void getMagXYZ(Vector3f &magXYZ) const
uint32_t lastVelReset_ms
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
void getAccelNED(Vector3f &accelNED) const
bool getHeightControlLimit(float &height) const
bool is_nan(void) const
Definition: quaternion.h:59
static AP_GPS gps
Definition: AHRS_Test.cpp:22
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
float length(void) const
Definition: quaternion.cpp:287
bool getLLH(struct Location &loc) const
float hgtInnovFiltState
struct Location EKF_origin
NavEKF3 * frontend
nav_filter_status filterStatus
Vector3f beaconPosNED
uint32_t imuSampleTime_ms
void send_status_report(mavlink_channel_t chan)
Vector3 varInnovBodyVel
uint32_t prevBodyVelFuseTime_ms
void zero()
Definition: vector3.h:182
bool getOriginLLH(struct Location &loc) const
uint32_t lastGpsVelFail_ms
AP_Int8 _useRngSwHgt
Definition: AP_NavEKF3.h:407
T x
Definition: vector3.h:67
void getFilterTimeouts(uint8_t &timeouts) const
float bcnPosDownOffsetMin
Vector3f receiverPos