AP_NavEKF3_RngBcnFusion.cpp 26 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641
  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 <GCS_MAVLink/GCS.h>
  7. extern const AP_HAL::HAL& hal;
  8. /********************************************************
  9. * FUSE MEASURED_DATA *
  10. ********************************************************/
  11. // select fusion of range beacon measurements
  12. void NavEKF3_core::SelectRngBcnFusion()
  13. {
  14. // read range data from the sensor and check for new data in the buffer
  15. readRngBcnData();
  16. // Determine if we need to fuse range beacon data on this time step
  17. if (rngBcnDataToFuse) {
  18. if (PV_AidingMode == AID_ABSOLUTE) {
  19. if (!filterStatus.flags.using_gps && rngBcnAlignmentCompleted) {
  20. if (!bcnOriginEstInit) {
  21. bcnOriginEstInit = true;
  22. bcnPosOffsetNED.x = receiverPos.x - stateStruct.position.x;
  23. bcnPosOffsetNED.y = receiverPos.y - stateStruct.position.y;
  24. }
  25. // If we aren't using GPS, then the beacons are used as the primary means of position reference
  26. FuseRngBcn();
  27. } else {
  28. // If we are using GPS, then GPS is the primary reference, but we continue to use the beacon data
  29. // to calculate an independant position that is used to update the beacon position offset if we need to
  30. // start using beacon data as the primary reference.
  31. FuseRngBcnStatic();
  32. // record that the beacon origin needs to be initialised
  33. bcnOriginEstInit = false;
  34. }
  35. } else {
  36. // If we aren't able to use the data in the main filter, use a simple 3-state filter to estimate position only
  37. FuseRngBcnStatic();
  38. // record that the beacon origin needs to be initialised
  39. bcnOriginEstInit = false;
  40. }
  41. }
  42. }
  43. void NavEKF3_core::FuseRngBcn()
  44. {
  45. // declarations
  46. float pn;
  47. float pe;
  48. float pd;
  49. float bcn_pn;
  50. float bcn_pe;
  51. float bcn_pd;
  52. const float R_BCN = sq(MAX(rngBcnDataDelayed.rngErr , 0.1f));
  53. float rngPred;
  54. // health is set bad until test passed
  55. rngBcnHealth = false;
  56. if (activeHgtSource != HGT_SOURCE_BCN) {
  57. // calculate the vertical offset from EKF datum to beacon datum
  58. CalcRangeBeaconPosDownOffset(R_BCN, stateStruct.position, false);
  59. } else {
  60. bcnPosOffsetNED.z = 0.0f;
  61. }
  62. // copy required states to local variable names
  63. pn = stateStruct.position.x;
  64. pe = stateStruct.position.y;
  65. pd = stateStruct.position.z;
  66. bcn_pn = rngBcnDataDelayed.beacon_posNED.x;
  67. bcn_pe = rngBcnDataDelayed.beacon_posNED.y;
  68. bcn_pd = rngBcnDataDelayed.beacon_posNED.z + bcnPosOffsetNED.z;
  69. // predicted range
  70. Vector3f deltaPosNED = stateStruct.position - rngBcnDataDelayed.beacon_posNED;
  71. rngPred = deltaPosNED.length();
  72. // calculate measurement innovation
  73. innovRngBcn = rngPred - rngBcnDataDelayed.rng;
  74. // perform fusion of range measurement
  75. if (rngPred > 0.1f)
  76. {
  77. // calculate observation jacobians
  78. float H_BCN[24];
  79. memset(H_BCN, 0, sizeof(H_BCN));
  80. float t2 = bcn_pd-pd;
  81. float t3 = bcn_pe-pe;
  82. float t4 = bcn_pn-pn;
  83. float t5 = t2*t2;
  84. float t6 = t3*t3;
  85. float t7 = t4*t4;
  86. float t8 = t5+t6+t7;
  87. float t9 = 1.0f/sqrtf(t8);
  88. H_BCN[7] = -t4*t9;
  89. H_BCN[8] = -t3*t9;
  90. // If we are not using the beacons as a height reference, we pretend that the beacons
  91. // are at the same height as the flight vehicle when calculating the observation derivatives
  92. // and Kalman gains
  93. // TODO - less hacky way of achieving this, preferably using an alternative derivation
  94. if (activeHgtSource != HGT_SOURCE_BCN) {
  95. t2 = 0.0f;
  96. }
  97. H_BCN[9] = -t2*t9;
  98. // calculate Kalman gains
  99. float t10 = P[9][9]*t2*t9;
  100. float t11 = P[8][9]*t3*t9;
  101. float t12 = P[7][9]*t4*t9;
  102. float t13 = t10+t11+t12;
  103. float t14 = t2*t9*t13;
  104. float t15 = P[9][8]*t2*t9;
  105. float t16 = P[8][8]*t3*t9;
  106. float t17 = P[7][8]*t4*t9;
  107. float t18 = t15+t16+t17;
  108. float t19 = t3*t9*t18;
  109. float t20 = P[9][7]*t2*t9;
  110. float t21 = P[8][7]*t3*t9;
  111. float t22 = P[7][7]*t4*t9;
  112. float t23 = t20+t21+t22;
  113. float t24 = t4*t9*t23;
  114. varInnovRngBcn = R_BCN+t14+t19+t24;
  115. float t26;
  116. if (varInnovRngBcn >= R_BCN) {
  117. t26 = 1.0f/varInnovRngBcn;
  118. faultStatus.bad_rngbcn = false;
  119. } else {
  120. // the calculation is badly conditioned, so we cannot perform fusion on this step
  121. // we reset the covariance matrix and try again next measurement
  122. CovarianceInit();
  123. faultStatus.bad_rngbcn = true;
  124. return;
  125. }
  126. Kfusion[0] = -t26*(P[0][7]*t4*t9+P[0][8]*t3*t9+P[0][9]*t2*t9);
  127. Kfusion[1] = -t26*(P[1][7]*t4*t9+P[1][8]*t3*t9+P[1][9]*t2*t9);
  128. Kfusion[2] = -t26*(P[2][7]*t4*t9+P[2][8]*t3*t9+P[2][9]*t2*t9);
  129. Kfusion[3] = -t26*(P[3][7]*t4*t9+P[3][8]*t3*t9+P[3][9]*t2*t9);
  130. Kfusion[4] = -t26*(P[4][7]*t4*t9+P[4][8]*t3*t9+P[4][9]*t2*t9);
  131. Kfusion[5] = -t26*(P[5][7]*t4*t9+P[5][8]*t3*t9+P[5][9]*t2*t9);
  132. Kfusion[7] = -t26*(t22+P[7][8]*t3*t9+P[7][9]*t2*t9);
  133. Kfusion[8] = -t26*(t16+P[8][7]*t4*t9+P[8][9]*t2*t9);
  134. if (!inhibitDelAngBiasStates) {
  135. Kfusion[10] = -t26*(P[10][7]*t4*t9+P[10][8]*t3*t9+P[10][9]*t2*t9);
  136. Kfusion[11] = -t26*(P[11][7]*t4*t9+P[11][8]*t3*t9+P[11][9]*t2*t9);
  137. Kfusion[12] = -t26*(P[12][7]*t4*t9+P[12][8]*t3*t9+P[12][9]*t2*t9);
  138. } else {
  139. // zero indexes 10 to 12 = 3*4 bytes
  140. memset(&Kfusion[10], 0, 12);
  141. }
  142. if (!inhibitDelVelBiasStates) {
  143. Kfusion[13] = -t26*(P[13][7]*t4*t9+P[13][8]*t3*t9+P[13][9]*t2*t9);
  144. Kfusion[14] = -t26*(P[14][7]*t4*t9+P[14][8]*t3*t9+P[14][9]*t2*t9);
  145. Kfusion[15] = -t26*(P[15][7]*t4*t9+P[15][8]*t3*t9+P[15][9]*t2*t9);
  146. } else {
  147. // zero indexes 13 to 15 = 3*4 bytes
  148. memset(&Kfusion[13], 0, 12);
  149. }
  150. // only allow the range observations to modify the vertical states if we are using it as a height reference
  151. if (activeHgtSource == HGT_SOURCE_BCN) {
  152. Kfusion[6] = -t26*(P[6][7]*t4*t9+P[6][8]*t3*t9+P[6][9]*t2*t9);
  153. Kfusion[9] = -t26*(t10+P[9][7]*t4*t9+P[9][8]*t3*t9);
  154. } else {
  155. Kfusion[6] = 0.0f;
  156. Kfusion[9] = 0.0f;
  157. }
  158. if (!inhibitMagStates) {
  159. Kfusion[16] = -t26*(P[16][7]*t4*t9+P[16][8]*t3*t9+P[16][9]*t2*t9);
  160. Kfusion[17] = -t26*(P[17][7]*t4*t9+P[17][8]*t3*t9+P[17][9]*t2*t9);
  161. Kfusion[18] = -t26*(P[18][7]*t4*t9+P[18][8]*t3*t9+P[18][9]*t2*t9);
  162. Kfusion[19] = -t26*(P[19][7]*t4*t9+P[19][8]*t3*t9+P[19][9]*t2*t9);
  163. Kfusion[20] = -t26*(P[20][7]*t4*t9+P[20][8]*t3*t9+P[20][9]*t2*t9);
  164. Kfusion[21] = -t26*(P[21][7]*t4*t9+P[21][8]*t3*t9+P[21][9]*t2*t9);
  165. } else {
  166. // zero indexes 16 to 21 = 6*4 bytes
  167. memset(&Kfusion[16], 0, 24);
  168. }
  169. if (!inhibitWindStates) {
  170. Kfusion[22] = -t26*(P[22][7]*t4*t9+P[22][8]*t3*t9+P[22][9]*t2*t9);
  171. Kfusion[23] = -t26*(P[23][7]*t4*t9+P[23][8]*t3*t9+P[23][9]*t2*t9);
  172. } else {
  173. // zero indexes 22 to 23 = 2*4 bytes
  174. memset(&Kfusion[22], 0, 8);
  175. }
  176. // Calculate innovation using the selected offset value
  177. Vector3f delta = stateStruct.position - rngBcnDataDelayed.beacon_posNED;
  178. innovRngBcn = delta.length() - rngBcnDataDelayed.rng;
  179. // calculate the innovation consistency test ratio
  180. rngBcnTestRatio = sq(innovRngBcn) / (sq(MAX(0.01f * (float)frontend->_rngBcnInnovGate, 1.0f)) * varInnovRngBcn);
  181. // fail if the ratio is > 1, but don't fail if bad IMU data
  182. rngBcnHealth = ((rngBcnTestRatio < 1.0f) || badIMUdata);
  183. // test the ratio before fusing data
  184. if (rngBcnHealth) {
  185. // restart the counter
  186. lastRngBcnPassTime_ms = imuSampleTime_ms;
  187. // correct the covariance P = (I - K*H)*P
  188. // take advantage of the empty columns in KH to reduce the
  189. // number of operations
  190. for (unsigned i = 0; i<=stateIndexLim; i++) {
  191. for (unsigned j = 0; j<=6; j++) {
  192. KH[i][j] = 0.0f;
  193. }
  194. for (unsigned j = 7; j<=9; j++) {
  195. KH[i][j] = Kfusion[i] * H_BCN[j];
  196. }
  197. for (unsigned j = 10; j<=23; j++) {
  198. KH[i][j] = 0.0f;
  199. }
  200. }
  201. for (unsigned j = 0; j<=stateIndexLim; j++) {
  202. for (unsigned i = 0; i<=stateIndexLim; i++) {
  203. ftype res = 0;
  204. res += KH[i][7] * P[7][j];
  205. res += KH[i][8] * P[8][j];
  206. res += KH[i][9] * P[9][j];
  207. KHP[i][j] = res;
  208. }
  209. }
  210. // Check that we are not going to drive any variances negative and skip the update if so
  211. bool healthyFusion = true;
  212. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  213. if (KHP[i][i] > P[i][i]) {
  214. healthyFusion = false;
  215. }
  216. }
  217. if (healthyFusion) {
  218. // update the covariance matrix
  219. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  220. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  221. P[i][j] = P[i][j] - KHP[i][j];
  222. }
  223. }
  224. // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
  225. ForceSymmetry();
  226. ConstrainVariances();
  227. // correct the state vector
  228. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  229. statesArray[j] = statesArray[j] - Kfusion[j] * innovRngBcn;
  230. }
  231. // record healthy fusion
  232. faultStatus.bad_rngbcn = false;
  233. } else {
  234. // record bad fusion
  235. faultStatus.bad_rngbcn = true;
  236. }
  237. }
  238. // Update the fusion report
  239. rngBcnFusionReport[rngBcnDataDelayed.beacon_ID].beaconPosNED = rngBcnDataDelayed.beacon_posNED;
  240. rngBcnFusionReport[rngBcnDataDelayed.beacon_ID].innov = innovRngBcn;
  241. rngBcnFusionReport[rngBcnDataDelayed.beacon_ID].innovVar = varInnovRngBcn;
  242. rngBcnFusionReport[rngBcnDataDelayed.beacon_ID].rng = rngBcnDataDelayed.rng;
  243. rngBcnFusionReport[rngBcnDataDelayed.beacon_ID].testRatio = rngBcnTestRatio;
  244. }
  245. }
  246. /*
  247. Use range beacon measurements to calculate a static position using a 3-state EKF algorithm.
  248. Algorithm based on the following:
  249. https://github.com/priseborough/InertialNav/blob/master/derivations/range_beacon.m
  250. */
  251. void NavEKF3_core::FuseRngBcnStatic()
  252. {
  253. // get the estimated range measurement variance
  254. const float R_RNG = sq(MAX(rngBcnDataDelayed.rngErr , 0.1f));
  255. /*
  256. The first thing to do is to check if we have started the alignment and if not, initialise the
  257. states and covariance to a first guess. To do this iterate through the available beacons and then
  258. initialise the initial position to the mean beacon position. The initial position uncertainty
  259. is set to the mean range measurement.
  260. */
  261. if (!rngBcnAlignmentStarted) {
  262. if (rngBcnDataDelayed.beacon_ID != lastBeaconIndex) {
  263. rngBcnPosSum += rngBcnDataDelayed.beacon_posNED;
  264. lastBeaconIndex = rngBcnDataDelayed.beacon_ID;
  265. rngSum += rngBcnDataDelayed.rng;
  266. numBcnMeas++;
  267. // capture the beacon vertical spread
  268. if (rngBcnDataDelayed.beacon_posNED.z > maxBcnPosD) {
  269. maxBcnPosD = rngBcnDataDelayed.beacon_posNED.z;
  270. } else if(rngBcnDataDelayed.beacon_posNED.z < minBcnPosD) {
  271. minBcnPosD = rngBcnDataDelayed.beacon_posNED.z;
  272. }
  273. }
  274. if (numBcnMeas >= 100) {
  275. rngBcnAlignmentStarted = true;
  276. float tempVar = 1.0f / (float)numBcnMeas;
  277. // initialise the receiver position to the centre of the beacons and at zero height
  278. receiverPos.x = rngBcnPosSum.x * tempVar;
  279. receiverPos.y = rngBcnPosSum.y * tempVar;
  280. receiverPos.z = 0.0f;
  281. receiverPosCov[2][2] = receiverPosCov[1][1] = receiverPosCov[0][0] = rngSum * tempVar;
  282. lastBeaconIndex = 0;
  283. numBcnMeas = 0;
  284. rngBcnPosSum.zero();
  285. rngSum = 0.0f;
  286. }
  287. }
  288. if (rngBcnAlignmentStarted) {
  289. numBcnMeas++;
  290. if (numBcnMeas >= 100) {
  291. // 100 observations is enough for a stable estimate under most conditions
  292. // TODO monitor stability of the position estimate
  293. rngBcnAlignmentCompleted = true;
  294. }
  295. if (rngBcnAlignmentCompleted) {
  296. if (activeHgtSource != HGT_SOURCE_BCN) {
  297. // We are using a different height reference for the main EKF so need to estimate a vertical
  298. // position offset to be applied to the beacon system that minimises the range innovations
  299. // The position estimate should be stable after 100 iterations so we use a simple dual
  300. // hypothesis 1-state EKF to estimate the offset
  301. Vector3f refPosNED;
  302. refPosNED.x = receiverPos.x;
  303. refPosNED.y = receiverPos.y;
  304. refPosNED.z = stateStruct.position.z;
  305. CalcRangeBeaconPosDownOffset(R_RNG, refPosNED, true);
  306. } else {
  307. // we are using the beacons as the primary height source, so don't modify their vertical position
  308. bcnPosOffsetNED.z = 0.0f;
  309. }
  310. } else {
  311. if (activeHgtSource != HGT_SOURCE_BCN) {
  312. // The position estimate is not yet stable so we cannot run the 1-state EKF to estimate
  313. // beacon system vertical position offset. Instead we initialise the dual hypothesis offset states
  314. // using the beacon vertical position, vertical position estimate relative to the beacon origin
  315. // and the main EKF vertical position
  316. // Calculate the mid vertical position of all beacons
  317. float bcnMidPosD = 0.5f * (minBcnPosD + maxBcnPosD);
  318. // calculate the delta to the estimated receiver position
  319. float delta = receiverPos.z - bcnMidPosD;
  320. // calcuate the two hypothesis for our vertical position
  321. float receverPosDownMax;
  322. float receverPosDownMin;
  323. if (delta >= 0.0f) {
  324. receverPosDownMax = receiverPos.z;
  325. receverPosDownMin = receiverPos.z - 2.0f * delta;
  326. } else {
  327. receverPosDownMax = receiverPos.z - 2.0f * delta;
  328. receverPosDownMin = receiverPos.z;
  329. }
  330. bcnPosDownOffsetMax = stateStruct.position.z - receverPosDownMin;
  331. bcnPosDownOffsetMin = stateStruct.position.z - receverPosDownMax;
  332. } else {
  333. // We are using the beacons as the primary height reference, so don't modify their vertical position
  334. bcnPosOffsetNED.z = 0.0f;
  335. }
  336. }
  337. // Add some process noise to the states at each time step
  338. for (uint8_t i= 0; i<=2; i++) {
  339. receiverPosCov[i][i] += 0.1f;
  340. }
  341. // calculate the observation jacobian
  342. float t2 = rngBcnDataDelayed.beacon_posNED.z - receiverPos.z + bcnPosOffsetNED.z;
  343. float t3 = rngBcnDataDelayed.beacon_posNED.y - receiverPos.y;
  344. float t4 = rngBcnDataDelayed.beacon_posNED.x - receiverPos.x;
  345. float t5 = t2*t2;
  346. float t6 = t3*t3;
  347. float t7 = t4*t4;
  348. float t8 = t5+t6+t7;
  349. if (t8 < 0.1f) {
  350. // calculation will be badly conditioned
  351. return;
  352. }
  353. float t9 = 1.0f/sqrtf(t8);
  354. float t10 = rngBcnDataDelayed.beacon_posNED.x*2.0f;
  355. float t15 = receiverPos.x*2.0f;
  356. float t11 = t10-t15;
  357. float t12 = rngBcnDataDelayed.beacon_posNED.y*2.0f;
  358. float t14 = receiverPos.y*2.0f;
  359. float t13 = t12-t14;
  360. float t16 = rngBcnDataDelayed.beacon_posNED.z*2.0f;
  361. float t18 = receiverPos.z*2.0f;
  362. float t17 = t16-t18;
  363. float H_RNG[3];
  364. H_RNG[0] = -t9*t11*0.5f;
  365. H_RNG[1] = -t9*t13*0.5f;
  366. H_RNG[2] = -t9*t17*0.5f;
  367. // calculate the Kalman gains
  368. float t19 = receiverPosCov[0][0]*t9*t11*0.5f;
  369. float t20 = receiverPosCov[1][1]*t9*t13*0.5f;
  370. float t21 = receiverPosCov[0][1]*t9*t11*0.5f;
  371. float t22 = receiverPosCov[2][1]*t9*t17*0.5f;
  372. float t23 = t20+t21+t22;
  373. float t24 = t9*t13*t23*0.5f;
  374. float t25 = receiverPosCov[1][2]*t9*t13*0.5f;
  375. float t26 = receiverPosCov[0][2]*t9*t11*0.5f;
  376. float t27 = receiverPosCov[2][2]*t9*t17*0.5f;
  377. float t28 = t25+t26+t27;
  378. float t29 = t9*t17*t28*0.5f;
  379. float t30 = receiverPosCov[1][0]*t9*t13*0.5f;
  380. float t31 = receiverPosCov[2][0]*t9*t17*0.5f;
  381. float t32 = t19+t30+t31;
  382. float t33 = t9*t11*t32*0.5f;
  383. varInnovRngBcn = R_RNG+t24+t29+t33;
  384. float t35 = 1.0f/varInnovRngBcn;
  385. float K_RNG[3];
  386. K_RNG[0] = -t35*(t19+receiverPosCov[0][1]*t9*t13*0.5f+receiverPosCov[0][2]*t9*t17*0.5f);
  387. K_RNG[1] = -t35*(t20+receiverPosCov[1][0]*t9*t11*0.5f+receiverPosCov[1][2]*t9*t17*0.5f);
  388. K_RNG[2] = -t35*(t27+receiverPosCov[2][0]*t9*t11*0.5f+receiverPosCov[2][1]*t9*t13*0.5f);
  389. // calculate range measurement innovation
  390. Vector3f deltaPosNED = receiverPos - rngBcnDataDelayed.beacon_posNED;
  391. deltaPosNED.z -= bcnPosOffsetNED.z;
  392. innovRngBcn = deltaPosNED.length() - rngBcnDataDelayed.rng;
  393. // calculate the innovation consistency test ratio
  394. rngBcnTestRatio = sq(innovRngBcn) / (sq(MAX(0.01f * (float)frontend->_rngBcnInnovGate, 1.0f)) * varInnovRngBcn);
  395. // fail if the ratio is > 1, but don't fail if bad IMU data
  396. rngBcnHealth = ((rngBcnTestRatio < 1.0f) || badIMUdata || !rngBcnAlignmentCompleted);
  397. // test the ratio before fusing data
  398. if (rngBcnHealth) {
  399. // update the state
  400. receiverPos.x -= K_RNG[0] * innovRngBcn;
  401. receiverPos.y -= K_RNG[1] * innovRngBcn;
  402. receiverPos.z -= K_RNG[2] * innovRngBcn;
  403. // calculate the covariance correction
  404. for (unsigned i = 0; i<=2; i++) {
  405. for (unsigned j = 0; j<=2; j++) {
  406. KH[i][j] = K_RNG[i] * H_RNG[j];
  407. }
  408. }
  409. for (unsigned j = 0; j<=2; j++) {
  410. for (unsigned i = 0; i<=2; i++) {
  411. ftype res = 0;
  412. res += KH[i][0] * receiverPosCov[0][j];
  413. res += KH[i][1] * receiverPosCov[1][j];
  414. res += KH[i][2] * receiverPosCov[2][j];
  415. KHP[i][j] = res;
  416. }
  417. }
  418. // prevent negative variances
  419. for (uint8_t i= 0; i<=2; i++) {
  420. if (receiverPosCov[i][i] < 0.0f) {
  421. receiverPosCov[i][i] = 0.0f;
  422. KHP[i][i] = 0.0f;
  423. } else if (KHP[i][i] > receiverPosCov[i][i]) {
  424. KHP[i][i] = receiverPosCov[i][i];
  425. }
  426. }
  427. // apply the covariance correction
  428. for (uint8_t i= 0; i<=2; i++) {
  429. for (uint8_t j= 0; j<=2; j++) {
  430. receiverPosCov[i][j] -= KHP[i][j];
  431. }
  432. }
  433. // ensure the covariance matrix is symmetric
  434. for (uint8_t i=1; i<=2; i++) {
  435. for (uint8_t j=0; j<=i-1; j++) {
  436. float temp = 0.5f*(receiverPosCov[i][j] + receiverPosCov[j][i]);
  437. receiverPosCov[i][j] = temp;
  438. receiverPosCov[j][i] = temp;
  439. }
  440. }
  441. }
  442. if (numBcnMeas >= 100) {
  443. // 100 observations is enough for a stable estimate under most conditions
  444. // TODO monitor stability of the position estimate
  445. rngBcnAlignmentCompleted = true;
  446. }
  447. // Update the fusion report
  448. rngBcnFusionReport[rngBcnDataDelayed.beacon_ID].beaconPosNED = rngBcnDataDelayed.beacon_posNED;
  449. rngBcnFusionReport[rngBcnDataDelayed.beacon_ID].innov = innovRngBcn;
  450. rngBcnFusionReport[rngBcnDataDelayed.beacon_ID].innovVar = varInnovRngBcn;
  451. rngBcnFusionReport[rngBcnDataDelayed.beacon_ID].rng = rngBcnDataDelayed.rng;
  452. rngBcnFusionReport[rngBcnDataDelayed.beacon_ID].testRatio = rngBcnTestRatio;
  453. }
  454. }
  455. /*
  456. Run a single state Kalman filter to estimate the vertical position offset of the range beacon constellation
  457. Calculate using a high and low hypothesis and select the hypothesis with the lowest innovation sequence
  458. */
  459. void NavEKF3_core::CalcRangeBeaconPosDownOffset(float obsVar, Vector3f &vehiclePosNED, bool aligning)
  460. {
  461. // Handle height offsets between the primary height source and the range beacons by estimating
  462. // the beacon systems global vertical position offset using a single state Kalman filter
  463. // The estimated offset is used to correct the beacon height when calculating innovations
  464. // A high and low estimate is calculated to handle the ambiguity in height associated with beacon positions that are co-planar
  465. // The main filter then uses the offset with the smaller innovations
  466. float innov; // range measurement innovation (m)
  467. float innovVar; // range measurement innovation variance (m^2)
  468. float gain; // Kalman gain
  469. float obsDeriv; // derivative of observation relative to state
  470. const float stateNoiseVar = 0.1f; // State process noise variance
  471. const float filtAlpha = 0.1f; // LPF constant
  472. const float innovGateWidth = 5.0f; // width of innovation consistency check gate in std
  473. // estimate upper value for offset
  474. // calculate observation derivative
  475. float t2 = rngBcnDataDelayed.beacon_posNED.z - vehiclePosNED.z + bcnPosDownOffsetMax;
  476. float t3 = rngBcnDataDelayed.beacon_posNED.y - vehiclePosNED.y;
  477. float t4 = rngBcnDataDelayed.beacon_posNED.x - vehiclePosNED.x;
  478. float t5 = t2*t2;
  479. float t6 = t3*t3;
  480. float t7 = t4*t4;
  481. float t8 = t5+t6+t7;
  482. float t9;
  483. if (t8 > 0.1f) {
  484. t9 = 1.0f/sqrtf(t8);
  485. obsDeriv = t2*t9;
  486. // Calculate innovation
  487. innov = sqrtf(t8) - rngBcnDataDelayed.rng;
  488. // covariance prediction
  489. bcnPosOffsetMaxVar += stateNoiseVar;
  490. // calculate the innovation variance
  491. innovVar = obsDeriv * bcnPosOffsetMaxVar * obsDeriv + obsVar;
  492. innovVar = MAX(innovVar, obsVar);
  493. // calculate the Kalman gain
  494. gain = (bcnPosOffsetMaxVar * obsDeriv) / innovVar;
  495. // calculate a filtered state change magnitude to be used to select between the high or low offset
  496. float stateChange = innov * gain;
  497. maxOffsetStateChangeFilt = (1.0f - filtAlpha) * maxOffsetStateChangeFilt + fminf(fabsf(filtAlpha * stateChange) , 1.0f);
  498. // Reject range innovation spikes using a 5-sigma threshold unless aligning
  499. if ((sq(innov) < sq(innovGateWidth) * innovVar) || aligning) {
  500. // state update
  501. bcnPosDownOffsetMax -= stateChange;
  502. // covariance update
  503. bcnPosOffsetMaxVar -= gain * obsDeriv * bcnPosOffsetMaxVar;
  504. bcnPosOffsetMaxVar = MAX(bcnPosOffsetMaxVar, 0.0f);
  505. }
  506. }
  507. // estimate lower value for offset
  508. // calculate observation derivative
  509. t2 = rngBcnDataDelayed.beacon_posNED.z - vehiclePosNED.z + bcnPosDownOffsetMin;
  510. t5 = t2*t2;
  511. t8 = t5+t6+t7;
  512. if (t8 > 0.1f) {
  513. t9 = 1.0f/sqrtf(t8);
  514. obsDeriv = t2*t9;
  515. // Calculate innovation
  516. innov = sqrtf(t8) - rngBcnDataDelayed.rng;
  517. // covariance prediction
  518. bcnPosOffsetMinVar += stateNoiseVar;
  519. // calculate the innovation variance
  520. innovVar = obsDeriv * bcnPosOffsetMinVar * obsDeriv + obsVar;
  521. innovVar = MAX(innovVar, obsVar);
  522. // calculate the Kalman gain
  523. gain = (bcnPosOffsetMinVar * obsDeriv) / innovVar;
  524. // calculate a filtered state change magnitude to be used to select between the high or low offset
  525. float stateChange = innov * gain;
  526. minOffsetStateChangeFilt = (1.0f - filtAlpha) * minOffsetStateChangeFilt + fminf(fabsf(filtAlpha * stateChange) , 1.0f);
  527. // Reject range innovation spikes using a 5-sigma threshold unless aligning
  528. if ((sq(innov) < sq(innovGateWidth) * innovVar) || aligning) {
  529. // state update
  530. bcnPosDownOffsetMin -= stateChange;
  531. // covariance update
  532. bcnPosOffsetMinVar -= gain * obsDeriv * bcnPosOffsetMinVar;
  533. bcnPosOffsetMinVar = MAX(bcnPosOffsetMinVar, 0.0f);
  534. }
  535. }
  536. // calculate the mid vertical position of all beacons
  537. float bcnMidPosD = 0.5f * (minBcnPosD + maxBcnPosD);
  538. // ensure the two beacon vertical offset hypothesis place the mid point of the beacons below and above the flight vehicle
  539. bcnPosDownOffsetMax = MAX(bcnPosDownOffsetMax, vehiclePosNED.z - bcnMidPosD + 0.5f);
  540. bcnPosDownOffsetMin = MIN(bcnPosDownOffsetMin, vehiclePosNED.z - bcnMidPosD - 0.5f);
  541. // calculate the innovation for the main filter using the offset that is most stable
  542. // apply hysteresis to prevent rapid switching
  543. if (!usingMinHypothesis && (minOffsetStateChangeFilt < (0.8f * maxOffsetStateChangeFilt))) {
  544. usingMinHypothesis = true;
  545. } else if (usingMinHypothesis && (maxOffsetStateChangeFilt < (0.8f * minOffsetStateChangeFilt))) {
  546. usingMinHypothesis = false;
  547. }
  548. if (usingMinHypothesis) {
  549. bcnPosOffsetNED.z = bcnPosDownOffsetMin;
  550. } else {
  551. bcnPosOffsetNED.z = bcnPosDownOffsetMax;
  552. }
  553. // apply the vertical offset to the beacon positions
  554. rngBcnDataDelayed.beacon_posNED.z += bcnPosOffsetNED.z;
  555. }