AP_NavEKF2_RngBcnFusion.cpp 23 KB

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