AP_NavEKF3_Outputs.cpp 25 KB

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