AP_NavEKF2_Outputs.cpp 24 KB

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