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