AP_NavEKF2_AirDataFusion.cpp 29 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439
  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 <stdio.h>
  7. extern const AP_HAL::HAL& hal;
  8. /********************************************************
  9. * RESET FUNCTIONS *
  10. ********************************************************/
  11. /********************************************************
  12. * FUSE MEASURED_DATA *
  13. ********************************************************/
  14. /*
  15. * Fuse true airspeed measurements using explicit algebraic equations generated with Matlab symbolic toolbox.
  16. * The script file used to generate these and other equations in this filter can be found here:
  17. * https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
  18. */
  19. void NavEKF2_core::FuseAirspeed()
  20. {
  21. // start performance timer
  22. hal.util->perf_begin(_perf_FuseAirspeed);
  23. // declarations
  24. float vn;
  25. float ve;
  26. float vd;
  27. float vwn;
  28. float vwe;
  29. float EAS2TAS = _ahrs->get_EAS2TAS();
  30. const float R_TAS = sq(constrain_float(frontend->_easNoise, 0.5f, 5.0f) * constrain_float(EAS2TAS, 0.9f, 10.0f));
  31. Vector3 SH_TAS;
  32. float SK_TAS;
  33. Vector24 H_TAS;
  34. float VtasPred;
  35. // health is set bad until test passed
  36. tasHealth = false;
  37. // copy required states to local variable names
  38. vn = stateStruct.velocity.x;
  39. ve = stateStruct.velocity.y;
  40. vd = stateStruct.velocity.z;
  41. vwn = stateStruct.wind_vel.x;
  42. vwe = stateStruct.wind_vel.y;
  43. // calculate the predicted airspeed
  44. VtasPred = norm((ve - vwe) , (vn - vwn) , vd);
  45. // perform fusion of True Airspeed measurement
  46. if (VtasPred > 1.0f)
  47. {
  48. // calculate observation jacobians
  49. SH_TAS[0] = 1.0f/(sqrtf(sq(ve - vwe) + sq(vn - vwn) + sq(vd)));
  50. SH_TAS[1] = (SH_TAS[0]*(2*ve - 2*vwe))/2;
  51. SH_TAS[2] = (SH_TAS[0]*(2*vn - 2*vwn))/2;
  52. for (uint8_t i=0; i<=2; i++) H_TAS[i] = 0.0f;
  53. H_TAS[3] = SH_TAS[2];
  54. H_TAS[4] = SH_TAS[1];
  55. H_TAS[5] = vd*SH_TAS[0];
  56. H_TAS[22] = -SH_TAS[2];
  57. H_TAS[23] = -SH_TAS[1];
  58. for (uint8_t i=6; i<=21; i++) H_TAS[i] = 0.0f;
  59. // calculate Kalman gains
  60. float temp = (R_TAS + SH_TAS[2]*(P[3][3]*SH_TAS[2] + P[4][3]*SH_TAS[1] - P[22][3]*SH_TAS[2] - P[23][3]*SH_TAS[1] + P[5][3]*vd*SH_TAS[0]) + SH_TAS[1]*(P[3][4]*SH_TAS[2] + P[4][4]*SH_TAS[1] - P[22][4]*SH_TAS[2] - P[23][4]*SH_TAS[1] + P[5][4]*vd*SH_TAS[0]) - SH_TAS[2]*(P[3][22]*SH_TAS[2] + P[4][22]*SH_TAS[1] - P[22][22]*SH_TAS[2] - P[23][22]*SH_TAS[1] + P[5][22]*vd*SH_TAS[0]) - SH_TAS[1]*(P[3][23]*SH_TAS[2] + P[4][23]*SH_TAS[1] - P[22][23]*SH_TAS[2] - P[23][23]*SH_TAS[1] + P[5][23]*vd*SH_TAS[0]) + vd*SH_TAS[0]*(P[3][5]*SH_TAS[2] + P[4][5]*SH_TAS[1] - P[22][5]*SH_TAS[2] - P[23][5]*SH_TAS[1] + P[5][5]*vd*SH_TAS[0]));
  61. if (temp >= R_TAS) {
  62. SK_TAS = 1.0f / temp;
  63. faultStatus.bad_airspeed = false;
  64. } else {
  65. // the calculation is badly conditioned, so we cannot perform fusion on this step
  66. // we reset the covariance matrix and try again next measurement
  67. CovarianceInit();
  68. faultStatus.bad_airspeed = true;
  69. return;
  70. }
  71. Kfusion[0] = SK_TAS*(P[0][3]*SH_TAS[2] - P[0][22]*SH_TAS[2] + P[0][4]*SH_TAS[1] - P[0][23]*SH_TAS[1] + P[0][5]*vd*SH_TAS[0]);
  72. Kfusion[1] = SK_TAS*(P[1][3]*SH_TAS[2] - P[1][22]*SH_TAS[2] + P[1][4]*SH_TAS[1] - P[1][23]*SH_TAS[1] + P[1][5]*vd*SH_TAS[0]);
  73. Kfusion[2] = SK_TAS*(P[2][3]*SH_TAS[2] - P[2][22]*SH_TAS[2] + P[2][4]*SH_TAS[1] - P[2][23]*SH_TAS[1] + P[2][5]*vd*SH_TAS[0]);
  74. Kfusion[3] = SK_TAS*(P[3][3]*SH_TAS[2] - P[3][22]*SH_TAS[2] + P[3][4]*SH_TAS[1] - P[3][23]*SH_TAS[1] + P[3][5]*vd*SH_TAS[0]);
  75. Kfusion[4] = SK_TAS*(P[4][3]*SH_TAS[2] - P[4][22]*SH_TAS[2] + P[4][4]*SH_TAS[1] - P[4][23]*SH_TAS[1] + P[4][5]*vd*SH_TAS[0]);
  76. Kfusion[5] = SK_TAS*(P[5][3]*SH_TAS[2] - P[5][22]*SH_TAS[2] + P[5][4]*SH_TAS[1] - P[5][23]*SH_TAS[1] + P[5][5]*vd*SH_TAS[0]);
  77. Kfusion[6] = SK_TAS*(P[6][3]*SH_TAS[2] - P[6][22]*SH_TAS[2] + P[6][4]*SH_TAS[1] - P[6][23]*SH_TAS[1] + P[6][5]*vd*SH_TAS[0]);
  78. Kfusion[7] = SK_TAS*(P[7][3]*SH_TAS[2] - P[7][22]*SH_TAS[2] + P[7][4]*SH_TAS[1] - P[7][23]*SH_TAS[1] + P[7][5]*vd*SH_TAS[0]);
  79. Kfusion[8] = SK_TAS*(P[8][3]*SH_TAS[2] - P[8][22]*SH_TAS[2] + P[8][4]*SH_TAS[1] - P[8][23]*SH_TAS[1] + P[8][5]*vd*SH_TAS[0]);
  80. Kfusion[9] = SK_TAS*(P[9][3]*SH_TAS[2] - P[9][22]*SH_TAS[2] + P[9][4]*SH_TAS[1] - P[9][23]*SH_TAS[1] + P[9][5]*vd*SH_TAS[0]);
  81. Kfusion[10] = SK_TAS*(P[10][3]*SH_TAS[2] - P[10][22]*SH_TAS[2] + P[10][4]*SH_TAS[1] - P[10][23]*SH_TAS[1] + P[10][5]*vd*SH_TAS[0]);
  82. Kfusion[11] = SK_TAS*(P[11][3]*SH_TAS[2] - P[11][22]*SH_TAS[2] + P[11][4]*SH_TAS[1] - P[11][23]*SH_TAS[1] + P[11][5]*vd*SH_TAS[0]);
  83. Kfusion[12] = SK_TAS*(P[12][3]*SH_TAS[2] - P[12][22]*SH_TAS[2] + P[12][4]*SH_TAS[1] - P[12][23]*SH_TAS[1] + P[12][5]*vd*SH_TAS[0]);
  84. Kfusion[13] = SK_TAS*(P[13][3]*SH_TAS[2] - P[13][22]*SH_TAS[2] + P[13][4]*SH_TAS[1] - P[13][23]*SH_TAS[1] + P[13][5]*vd*SH_TAS[0]);
  85. Kfusion[14] = SK_TAS*(P[14][3]*SH_TAS[2] - P[14][22]*SH_TAS[2] + P[14][4]*SH_TAS[1] - P[14][23]*SH_TAS[1] + P[14][5]*vd*SH_TAS[0]);
  86. Kfusion[15] = SK_TAS*(P[15][3]*SH_TAS[2] - P[15][22]*SH_TAS[2] + P[15][4]*SH_TAS[1] - P[15][23]*SH_TAS[1] + P[15][5]*vd*SH_TAS[0]);
  87. Kfusion[22] = SK_TAS*(P[22][3]*SH_TAS[2] - P[22][22]*SH_TAS[2] + P[22][4]*SH_TAS[1] - P[22][23]*SH_TAS[1] + P[22][5]*vd*SH_TAS[0]);
  88. Kfusion[23] = SK_TAS*(P[23][3]*SH_TAS[2] - P[23][22]*SH_TAS[2] + P[23][4]*SH_TAS[1] - P[23][23]*SH_TAS[1] + P[23][5]*vd*SH_TAS[0]);
  89. // zero Kalman gains to inhibit magnetic field state estimation
  90. if (!inhibitMagStates) {
  91. Kfusion[16] = SK_TAS*(P[16][3]*SH_TAS[2] - P[16][22]*SH_TAS[2] + P[16][4]*SH_TAS[1] - P[16][23]*SH_TAS[1] + P[16][5]*vd*SH_TAS[0]);
  92. Kfusion[17] = SK_TAS*(P[17][3]*SH_TAS[2] - P[17][22]*SH_TAS[2] + P[17][4]*SH_TAS[1] - P[17][23]*SH_TAS[1] + P[17][5]*vd*SH_TAS[0]);
  93. Kfusion[18] = SK_TAS*(P[18][3]*SH_TAS[2] - P[18][22]*SH_TAS[2] + P[18][4]*SH_TAS[1] - P[18][23]*SH_TAS[1] + P[18][5]*vd*SH_TAS[0]);
  94. Kfusion[19] = SK_TAS*(P[19][3]*SH_TAS[2] - P[19][22]*SH_TAS[2] + P[19][4]*SH_TAS[1] - P[19][23]*SH_TAS[1] + P[19][5]*vd*SH_TAS[0]);
  95. Kfusion[20] = SK_TAS*(P[20][3]*SH_TAS[2] - P[20][22]*SH_TAS[2] + P[20][4]*SH_TAS[1] - P[20][23]*SH_TAS[1] + P[20][5]*vd*SH_TAS[0]);
  96. Kfusion[21] = SK_TAS*(P[21][3]*SH_TAS[2] - P[21][22]*SH_TAS[2] + P[21][4]*SH_TAS[1] - P[21][23]*SH_TAS[1] + P[21][5]*vd*SH_TAS[0]);
  97. } else {
  98. for (uint8_t i=16; i<=21; i++) {
  99. Kfusion[i] = 0.0f;
  100. }
  101. }
  102. // calculate measurement innovation variance
  103. varInnovVtas = 1.0f/SK_TAS;
  104. // calculate measurement innovation
  105. innovVtas = VtasPred - tasDataDelayed.tas;
  106. // calculate the innovation consistency test ratio
  107. tasTestRatio = sq(innovVtas) / (sq(MAX(0.01f * (float)frontend->_tasInnovGate, 1.0f)) * varInnovVtas);
  108. // fail if the ratio is > 1, but don't fail if bad IMU data
  109. tasHealth = ((tasTestRatio < 1.0f) || badIMUdata);
  110. tasTimeout = (imuSampleTime_ms - lastTasPassTime_ms) > frontend->tasRetryTime_ms;
  111. // test the ratio before fusing data, forcing fusion if airspeed and position are timed out as we have no choice but to try and use airspeed to constrain error growth
  112. if (tasHealth || (tasTimeout && posTimeout)) {
  113. // restart the counter
  114. lastTasPassTime_ms = imuSampleTime_ms;
  115. // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
  116. stateStruct.angErr.zero();
  117. // correct the state vector
  118. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  119. statesArray[j] = statesArray[j] - Kfusion[j] * innovVtas;
  120. }
  121. // the first 3 states represent the angular misalignment vector. This is
  122. // is used to correct the estimated quaternion on the current time step
  123. stateStruct.quat.rotate(stateStruct.angErr);
  124. // correct the covariance P = (I - K*H)*P
  125. // take advantage of the empty columns in KH to reduce the
  126. // number of operations
  127. for (unsigned i = 0; i<=stateIndexLim; i++) {
  128. for (unsigned j = 0; j<=2; j++) {
  129. KH[i][j] = 0.0f;
  130. }
  131. for (unsigned j = 3; j<=5; j++) {
  132. KH[i][j] = Kfusion[i] * H_TAS[j];
  133. }
  134. for (unsigned j = 6; j<=21; j++) {
  135. KH[i][j] = 0.0f;
  136. }
  137. for (unsigned j = 22; j<=23; j++) {
  138. KH[i][j] = Kfusion[i] * H_TAS[j];
  139. }
  140. }
  141. for (unsigned j = 0; j<=stateIndexLim; j++) {
  142. for (unsigned i = 0; i<=stateIndexLim; i++) {
  143. ftype res = 0;
  144. res += KH[i][3] * P[3][j];
  145. res += KH[i][4] * P[4][j];
  146. res += KH[i][5] * P[5][j];
  147. res += KH[i][22] * P[22][j];
  148. res += KH[i][23] * P[23][j];
  149. KHP[i][j] = res;
  150. }
  151. }
  152. for (unsigned i = 0; i<=stateIndexLim; i++) {
  153. for (unsigned j = 0; j<=stateIndexLim; j++) {
  154. P[i][j] = P[i][j] - KHP[i][j];
  155. }
  156. }
  157. }
  158. }
  159. // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
  160. ForceSymmetry();
  161. ConstrainVariances();
  162. // stop performance timer
  163. hal.util->perf_end(_perf_FuseAirspeed);
  164. }
  165. // select fusion of true airspeed measurements
  166. void NavEKF2_core::SelectTasFusion()
  167. {
  168. // Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
  169. // If so, don't fuse measurements on this time step to reduce frame over-runs
  170. // Only allow one time slip to prevent high rate magnetometer data locking out fusion of other measurements
  171. if (magFusePerformed && dtIMUavg < 0.005f && !airSpdFusionDelayed) {
  172. airSpdFusionDelayed = true;
  173. return;
  174. } else {
  175. airSpdFusionDelayed = false;
  176. }
  177. // get true airspeed measurement
  178. readAirSpdData();
  179. // If we haven't received airspeed data for a while, then declare the airspeed data as being timed out
  180. if (imuSampleTime_ms - tasDataNew.time_ms > frontend->tasRetryTime_ms) {
  181. tasTimeout = true;
  182. }
  183. // if the filter is initialised, wind states are not inhibited and we have data to fuse, then perform TAS fusion
  184. if (tasDataToFuse && statesInitialised && !inhibitWindStates) {
  185. FuseAirspeed();
  186. prevTasStep_ms = imuSampleTime_ms;
  187. }
  188. }
  189. // select fusion of synthetic sideslip measurements
  190. // synthetic sidelip fusion only works for fixed wing aircraft and relies on the average sideslip being close to zero
  191. // it requires a stable wind for best results and should not be used for aerobatic flight with manoeuvres that induce large sidslip angles (eg knife-edge, spins, etc)
  192. void NavEKF2_core::SelectBetaFusion()
  193. {
  194. // Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
  195. // If so, don't fuse measurements on this time step to reduce frame over-runs
  196. // Only allow one time slip to prevent high rate magnetometer data preventing fusion of other measurements
  197. if (magFusePerformed && dtIMUavg < 0.005f && !sideSlipFusionDelayed) {
  198. sideSlipFusionDelayed = true;
  199. return;
  200. } else {
  201. sideSlipFusionDelayed = false;
  202. }
  203. // set true when the fusion time interval has triggered
  204. bool f_timeTrigger = ((imuSampleTime_ms - prevBetaStep_ms) >= frontend->betaAvg_ms);
  205. // set true when use of synthetic sideslip fusion is necessary because we have limited sensor data or are dead reckoning position
  206. bool f_required = !(use_compass() && useAirspeed() && ((imuSampleTime_ms - lastPosPassTime_ms) < frontend->posRetryTimeNoVel_ms));
  207. // set true when sideslip fusion is feasible (requires zero sideslip assumption to be valid and use of wind states)
  208. bool f_feasible = (assume_zero_sideslip() && !inhibitWindStates);
  209. // use synthetic sideslip fusion if feasible, required and enough time has lapsed since the last fusion
  210. if (f_feasible && f_required && f_timeTrigger) {
  211. FuseSideslip();
  212. prevBetaStep_ms = imuSampleTime_ms;
  213. }
  214. }
  215. /*
  216. * Fuse synthetic sideslip measurement of zero using explicit algebraic equations generated with Matlab symbolic toolbox.
  217. * The script file used to generate these and other equations in this filter can be found here:
  218. * https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
  219. */
  220. void NavEKF2_core::FuseSideslip()
  221. {
  222. // start performance timer
  223. hal.util->perf_begin(_perf_FuseSideslip);
  224. // declarations
  225. float q0;
  226. float q1;
  227. float q2;
  228. float q3;
  229. float vn;
  230. float ve;
  231. float vd;
  232. float vwn;
  233. float vwe;
  234. const float R_BETA = 0.03f; // assume a sideslip angle RMS of ~10 deg
  235. Vector10 SH_BETA;
  236. Vector5 SK_BETA;
  237. Vector3f vel_rel_wind;
  238. Vector24 H_BETA;
  239. float innovBeta;
  240. // copy required states to local variable names
  241. q0 = stateStruct.quat[0];
  242. q1 = stateStruct.quat[1];
  243. q2 = stateStruct.quat[2];
  244. q3 = stateStruct.quat[3];
  245. vn = stateStruct.velocity.x;
  246. ve = stateStruct.velocity.y;
  247. vd = stateStruct.velocity.z;
  248. vwn = stateStruct.wind_vel.x;
  249. vwe = stateStruct.wind_vel.y;
  250. // calculate predicted wind relative velocity in NED
  251. vel_rel_wind.x = vn - vwn;
  252. vel_rel_wind.y = ve - vwe;
  253. vel_rel_wind.z = vd;
  254. // rotate into body axes
  255. vel_rel_wind = prevTnb * vel_rel_wind;
  256. // perform fusion of assumed sideslip = 0
  257. if (vel_rel_wind.x > 5.0f)
  258. {
  259. // Calculate observation jacobians
  260. SH_BETA[0] = (vn - vwn)*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) - vd*(2*q0*q2 - 2*q1*q3) + (ve - vwe)*(2*q0*q3 + 2*q1*q2);
  261. if (fabsf(SH_BETA[0]) <= 1e-9f) {
  262. faultStatus.bad_sideslip = true;
  263. return;
  264. } else {
  265. faultStatus.bad_sideslip = false;
  266. }
  267. SH_BETA[0] = (vn - vwn)*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) - vd*(2*q0*q2 - 2*q1*q3) + (ve - vwe)*(2*q0*q3 + 2*q1*q2);
  268. SH_BETA[1] = (ve - vwe)*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + vd*(2*q0*q1 + 2*q2*q3) - (vn - vwn)*(2*q0*q3 - 2*q1*q2);
  269. SH_BETA[2] = vd*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) - (ve - vwe)*(2*q0*q1 - 2*q2*q3) + (vn - vwn)*(2*q0*q2 + 2*q1*q3);
  270. SH_BETA[3] = 1/sq(SH_BETA[0]);
  271. SH_BETA[4] = (sq(q0) - sq(q1) + sq(q2) - sq(q3))/SH_BETA[0];
  272. SH_BETA[5] = sq(q0) + sq(q1) - sq(q2) - sq(q3);
  273. SH_BETA[6] = 1/SH_BETA[0];
  274. SH_BETA[7] = 2*q0*q3;
  275. SH_BETA[8] = SH_BETA[7] + 2*q1*q2;
  276. SH_BETA[9] = SH_BETA[7] - 2*q1*q2;
  277. H_BETA[0] = SH_BETA[2]*SH_BETA[6];
  278. H_BETA[1] = SH_BETA[1]*SH_BETA[2]*SH_BETA[3];
  279. H_BETA[2] = - sq(SH_BETA[1])*SH_BETA[3] - 1;
  280. H_BETA[3] = - SH_BETA[6]*SH_BETA[9] - SH_BETA[1]*SH_BETA[3]*SH_BETA[5];
  281. H_BETA[4] = SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8];
  282. H_BETA[5] = SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3);
  283. for (uint8_t i=6; i<=21; i++) {
  284. H_BETA[i] = 0.0f;
  285. }
  286. H_BETA[22] = SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5];
  287. H_BETA[23] = SH_BETA[1]*SH_BETA[3]*SH_BETA[8] - SH_BETA[4];
  288. // Calculate Kalman gains
  289. float temp = (R_BETA + (SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8])*(P[22][4]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][4]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][4]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][4]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][4]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][4]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][4]*SH_BETA[2]*SH_BETA[6] + P[1][4]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) - (SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8])*(P[22][23]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][23]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][23]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][23]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][23]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][23]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][23]*SH_BETA[2]*SH_BETA[6] + P[1][23]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) - (SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5])*(P[22][3]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][3]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][3]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][3]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][3]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][3]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][3]*SH_BETA[2]*SH_BETA[6] + P[1][3]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) + (SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5])*(P[22][22]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][22]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][22]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][22]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][22]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][22]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][22]*SH_BETA[2]*SH_BETA[6] + P[1][22]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) - (sq(SH_BETA[1])*SH_BETA[3] + 1)*(P[22][2]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][2]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][2]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][2]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][2]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][2]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][2]*SH_BETA[2]*SH_BETA[6] + P[1][2]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) + (SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3))*(P[22][5]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][5]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][5]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][5]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][5]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][5]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][5]*SH_BETA[2]*SH_BETA[6] + P[1][5]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) + SH_BETA[2]*SH_BETA[6]*(P[22][0]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][0]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][0]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][0]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][0]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][0]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][0]*SH_BETA[2]*SH_BETA[6] + P[1][0]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]) + SH_BETA[1]*SH_BETA[2]*SH_BETA[3]*(P[22][1]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[3][1]*(SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5]) - P[2][1]*(sq(SH_BETA[1])*SH_BETA[3] + 1) + P[5][1]*(SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3)) + P[4][1]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) - P[23][1]*(SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8]) + P[0][1]*SH_BETA[2]*SH_BETA[6] + P[1][1]*SH_BETA[1]*SH_BETA[2]*SH_BETA[3]));
  290. if (temp >= R_BETA) {
  291. SK_BETA[0] = 1.0f / temp;
  292. faultStatus.bad_sideslip = false;
  293. } else {
  294. // the calculation is badly conditioned, so we cannot perform fusion on this step
  295. // we reset the covariance matrix and try again next measurement
  296. CovarianceInit();
  297. faultStatus.bad_sideslip = true;
  298. return;
  299. }
  300. SK_BETA[1] = SH_BETA[6]*(2*q0*q1 + 2*q2*q3) + SH_BETA[1]*SH_BETA[3]*(2*q0*q2 - 2*q1*q3);
  301. SK_BETA[2] = SH_BETA[6]*SH_BETA[9] + SH_BETA[1]*SH_BETA[3]*SH_BETA[5];
  302. SK_BETA[3] = SH_BETA[4] - SH_BETA[1]*SH_BETA[3]*SH_BETA[8];
  303. SK_BETA[4] = sq(SH_BETA[1])*SH_BETA[3] + 1;
  304. Kfusion[0] = SK_BETA[0]*(P[0][5]*SK_BETA[1] - P[0][2]*SK_BETA[4] - P[0][3]*SK_BETA[2] + P[0][4]*SK_BETA[3] + P[0][22]*SK_BETA[2] - P[0][23]*SK_BETA[3] + P[0][0]*SH_BETA[6]*SH_BETA[2] + P[0][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  305. Kfusion[1] = SK_BETA[0]*(P[1][5]*SK_BETA[1] - P[1][2]*SK_BETA[4] - P[1][3]*SK_BETA[2] + P[1][4]*SK_BETA[3] + P[1][22]*SK_BETA[2] - P[1][23]*SK_BETA[3] + P[1][0]*SH_BETA[6]*SH_BETA[2] + P[1][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  306. Kfusion[2] = SK_BETA[0]*(P[2][5]*SK_BETA[1] - P[2][2]*SK_BETA[4] - P[2][3]*SK_BETA[2] + P[2][4]*SK_BETA[3] + P[2][22]*SK_BETA[2] - P[2][23]*SK_BETA[3] + P[2][0]*SH_BETA[6]*SH_BETA[2] + P[2][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  307. Kfusion[3] = SK_BETA[0]*(P[3][5]*SK_BETA[1] - P[3][2]*SK_BETA[4] - P[3][3]*SK_BETA[2] + P[3][4]*SK_BETA[3] + P[3][22]*SK_BETA[2] - P[3][23]*SK_BETA[3] + P[3][0]*SH_BETA[6]*SH_BETA[2] + P[3][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  308. Kfusion[4] = SK_BETA[0]*(P[4][5]*SK_BETA[1] - P[4][2]*SK_BETA[4] - P[4][3]*SK_BETA[2] + P[4][4]*SK_BETA[3] + P[4][22]*SK_BETA[2] - P[4][23]*SK_BETA[3] + P[4][0]*SH_BETA[6]*SH_BETA[2] + P[4][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  309. Kfusion[5] = SK_BETA[0]*(P[5][5]*SK_BETA[1] - P[5][2]*SK_BETA[4] - P[5][3]*SK_BETA[2] + P[5][4]*SK_BETA[3] + P[5][22]*SK_BETA[2] - P[5][23]*SK_BETA[3] + P[5][0]*SH_BETA[6]*SH_BETA[2] + P[5][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  310. Kfusion[6] = SK_BETA[0]*(P[6][5]*SK_BETA[1] - P[6][2]*SK_BETA[4] - P[6][3]*SK_BETA[2] + P[6][4]*SK_BETA[3] + P[6][22]*SK_BETA[2] - P[6][23]*SK_BETA[3] + P[6][0]*SH_BETA[6]*SH_BETA[2] + P[6][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  311. Kfusion[7] = SK_BETA[0]*(P[7][5]*SK_BETA[1] - P[7][2]*SK_BETA[4] - P[7][3]*SK_BETA[2] + P[7][4]*SK_BETA[3] + P[7][22]*SK_BETA[2] - P[7][23]*SK_BETA[3] + P[7][0]*SH_BETA[6]*SH_BETA[2] + P[7][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  312. Kfusion[8] = SK_BETA[0]*(P[8][5]*SK_BETA[1] - P[8][2]*SK_BETA[4] - P[8][3]*SK_BETA[2] + P[8][4]*SK_BETA[3] + P[8][22]*SK_BETA[2] - P[8][23]*SK_BETA[3] + P[8][0]*SH_BETA[6]*SH_BETA[2] + P[8][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  313. Kfusion[9] = SK_BETA[0]*(P[9][5]*SK_BETA[1] - P[9][2]*SK_BETA[4] - P[9][3]*SK_BETA[2] + P[9][4]*SK_BETA[3] + P[9][22]*SK_BETA[2] - P[9][23]*SK_BETA[3] + P[9][0]*SH_BETA[6]*SH_BETA[2] + P[9][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  314. Kfusion[10] = SK_BETA[0]*(P[10][5]*SK_BETA[1] - P[10][2]*SK_BETA[4] - P[10][3]*SK_BETA[2] + P[10][4]*SK_BETA[3] + P[10][22]*SK_BETA[2] - P[10][23]*SK_BETA[3] + P[10][0]*SH_BETA[6]*SH_BETA[2] + P[10][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  315. Kfusion[11] = SK_BETA[0]*(P[11][5]*SK_BETA[1] - P[11][2]*SK_BETA[4] - P[11][3]*SK_BETA[2] + P[11][4]*SK_BETA[3] + P[11][22]*SK_BETA[2] - P[11][23]*SK_BETA[3] + P[11][0]*SH_BETA[6]*SH_BETA[2] + P[11][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  316. Kfusion[12] = SK_BETA[0]*(P[12][5]*SK_BETA[1] - P[12][2]*SK_BETA[4] - P[12][3]*SK_BETA[2] + P[12][4]*SK_BETA[3] + P[12][22]*SK_BETA[2] - P[12][23]*SK_BETA[3] + P[12][0]*SH_BETA[6]*SH_BETA[2] + P[12][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  317. Kfusion[13] = SK_BETA[0]*(P[13][5]*SK_BETA[1] - P[13][2]*SK_BETA[4] - P[13][3]*SK_BETA[2] + P[13][4]*SK_BETA[3] + P[13][22]*SK_BETA[2] - P[13][23]*SK_BETA[3] + P[13][0]*SH_BETA[6]*SH_BETA[2] + P[13][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  318. Kfusion[14] = SK_BETA[0]*(P[14][5]*SK_BETA[1] - P[14][2]*SK_BETA[4] - P[14][3]*SK_BETA[2] + P[14][4]*SK_BETA[3] + P[14][22]*SK_BETA[2] - P[14][23]*SK_BETA[3] + P[14][0]*SH_BETA[6]*SH_BETA[2] + P[14][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  319. Kfusion[15] = SK_BETA[0]*(P[15][5]*SK_BETA[1] - P[15][2]*SK_BETA[4] - P[15][3]*SK_BETA[2] + P[15][4]*SK_BETA[3] + P[15][22]*SK_BETA[2] - P[15][23]*SK_BETA[3] + P[15][0]*SH_BETA[6]*SH_BETA[2] + P[15][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  320. Kfusion[22] = SK_BETA[0]*(P[22][5]*SK_BETA[1] - P[22][2]*SK_BETA[4] - P[22][3]*SK_BETA[2] + P[22][4]*SK_BETA[3] + P[22][22]*SK_BETA[2] - P[22][23]*SK_BETA[3] + P[22][0]*SH_BETA[6]*SH_BETA[2] + P[22][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  321. Kfusion[23] = SK_BETA[0]*(P[23][5]*SK_BETA[1] - P[23][2]*SK_BETA[4] - P[23][3]*SK_BETA[2] + P[23][4]*SK_BETA[3] + P[23][22]*SK_BETA[2] - P[23][23]*SK_BETA[3] + P[23][0]*SH_BETA[6]*SH_BETA[2] + P[23][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  322. // zero Kalman gains to inhibit magnetic field state estimation
  323. if (!inhibitMagStates) {
  324. Kfusion[16] = SK_BETA[0]*(P[16][5]*SK_BETA[1] - P[16][2]*SK_BETA[4] - P[16][3]*SK_BETA[2] + P[16][4]*SK_BETA[3] + P[16][22]*SK_BETA[2] - P[16][23]*SK_BETA[3] + P[16][0]*SH_BETA[6]*SH_BETA[2] + P[16][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  325. Kfusion[17] = SK_BETA[0]*(P[17][5]*SK_BETA[1] - P[17][2]*SK_BETA[4] - P[17][3]*SK_BETA[2] + P[17][4]*SK_BETA[3] + P[17][22]*SK_BETA[2] - P[17][23]*SK_BETA[3] + P[17][0]*SH_BETA[6]*SH_BETA[2] + P[17][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  326. Kfusion[18] = SK_BETA[0]*(P[18][5]*SK_BETA[1] - P[18][2]*SK_BETA[4] - P[18][3]*SK_BETA[2] + P[18][4]*SK_BETA[3] + P[18][22]*SK_BETA[2] - P[18][23]*SK_BETA[3] + P[18][0]*SH_BETA[6]*SH_BETA[2] + P[18][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  327. Kfusion[19] = SK_BETA[0]*(P[19][5]*SK_BETA[1] - P[19][2]*SK_BETA[4] - P[19][3]*SK_BETA[2] + P[19][4]*SK_BETA[3] + P[19][22]*SK_BETA[2] - P[19][23]*SK_BETA[3] + P[19][0]*SH_BETA[6]*SH_BETA[2] + P[19][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  328. Kfusion[20] = SK_BETA[0]*(P[20][5]*SK_BETA[1] - P[20][2]*SK_BETA[4] - P[20][3]*SK_BETA[2] + P[20][4]*SK_BETA[3] + P[20][22]*SK_BETA[2] - P[20][23]*SK_BETA[3] + P[20][0]*SH_BETA[6]*SH_BETA[2] + P[20][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  329. Kfusion[21] = SK_BETA[0]*(P[21][5]*SK_BETA[1] - P[21][2]*SK_BETA[4] - P[21][3]*SK_BETA[2] + P[21][4]*SK_BETA[3] + P[21][22]*SK_BETA[2] - P[21][23]*SK_BETA[3] + P[21][0]*SH_BETA[6]*SH_BETA[2] + P[21][1]*SH_BETA[1]*SH_BETA[3]*SH_BETA[2]);
  330. } else {
  331. for (uint8_t i=16; i<=21; i++) {
  332. Kfusion[i] = 0.0f;
  333. }
  334. }
  335. // calculate predicted sideslip angle and innovation using small angle approximation
  336. innovBeta = vel_rel_wind.y / vel_rel_wind.x;
  337. // reject measurement if greater than 3-sigma inconsistency
  338. if (innovBeta > 0.5f) {
  339. return;
  340. }
  341. // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
  342. stateStruct.angErr.zero();
  343. // correct the state vector
  344. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  345. statesArray[j] = statesArray[j] - Kfusion[j] * innovBeta;
  346. }
  347. // the first 3 states represent the angular misalignment vector. This is
  348. // is used to correct the estimated quaternion on the current time step
  349. stateStruct.quat.rotate(stateStruct.angErr);
  350. // correct the covariance P = (I - K*H)*P
  351. // take advantage of the empty columns in KH to reduce the
  352. // number of operations
  353. for (unsigned i = 0; i<=stateIndexLim; i++) {
  354. for (unsigned j = 0; j<=5; j++) {
  355. KH[i][j] = Kfusion[i] * H_BETA[j];
  356. }
  357. for (unsigned j = 6; j<=21; j++) {
  358. KH[i][j] = 0.0f;
  359. }
  360. for (unsigned j = 22; j<=23; j++) {
  361. KH[i][j] = Kfusion[i] * H_BETA[j];
  362. }
  363. }
  364. for (unsigned j = 0; j<=stateIndexLim; j++) {
  365. for (unsigned i = 0; i<=stateIndexLim; i++) {
  366. ftype res = 0;
  367. res += KH[i][0] * P[0][j];
  368. res += KH[i][1] * P[1][j];
  369. res += KH[i][2] * P[2][j];
  370. res += KH[i][3] * P[3][j];
  371. res += KH[i][4] * P[4][j];
  372. res += KH[i][5] * P[5][j];
  373. res += KH[i][22] * P[22][j];
  374. res += KH[i][23] * P[23][j];
  375. KHP[i][j] = res;
  376. }
  377. }
  378. for (unsigned i = 0; i<=stateIndexLim; i++) {
  379. for (unsigned j = 0; j<=stateIndexLim; j++) {
  380. P[i][j] = P[i][j] - KHP[i][j];
  381. }
  382. }
  383. }
  384. // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
  385. ForceSymmetry();
  386. ConstrainVariances();
  387. // stop the performance timer
  388. hal.util->perf_end(_perf_FuseSideslip);
  389. }
  390. /********************************************************
  391. * MISC FUNCTIONS *
  392. ********************************************************/