AP_NavEKF2_core.cpp 81 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650
  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 <AP_GPS/AP_GPS.h>
  8. #include <stdio.h>
  9. extern const AP_HAL::HAL& hal;
  10. #define earthRate 0.000072921f // earth rotation rate (rad/sec)
  11. // initial imu bias uncertainty (deg/sec)
  12. #define INIT_ACCEL_BIAS_UNCERTAINTY 0.5f
  13. // maximum allowed gyro bias (rad/sec)
  14. #define GYRO_BIAS_LIMIT 0.5f
  15. /*
  16. to run EK2 timing tests you need to set ENABLE_EKF_TIMING to 1, plus setup as follows:
  17. - copter at 400Hz
  18. - INS_FAST_SAMPLE=0
  19. - EKF2_MAG_CAL=4
  20. - GPS_TYPE=14
  21. - load fakegps in mavproxy
  22. - ensure a compass is enabled
  23. - wait till EK2 reports "using GPS" (this is important, ignore earlier results)
  24. DO NOT FLY WITH THIS ENABLED
  25. */
  26. #define ENABLE_EKF_TIMING 0
  27. // constructor
  28. NavEKF2_core::NavEKF2_core(NavEKF2 *_frontend) :
  29. _perf_UpdateFilter(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_UpdateFilter")),
  30. _perf_CovariancePrediction(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_CovariancePrediction")),
  31. _perf_FuseVelPosNED(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_FuseVelPosNED")),
  32. _perf_FuseMagnetometer(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_FuseMagnetometer")),
  33. _perf_FuseAirspeed(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_FuseAirspeed")),
  34. _perf_FuseSideslip(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_FuseSideslip")),
  35. _perf_TerrainOffset(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_TerrainOffset")),
  36. _perf_FuseOptFlow(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_FuseOptFlow")),
  37. frontend(_frontend)
  38. {
  39. _perf_test[0] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test0");
  40. _perf_test[1] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test1");
  41. _perf_test[2] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test2");
  42. _perf_test[3] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test3");
  43. _perf_test[4] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test4");
  44. _perf_test[5] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test5");
  45. _perf_test[6] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test6");
  46. _perf_test[7] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test7");
  47. _perf_test[8] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test8");
  48. _perf_test[9] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_Test9");
  49. }
  50. // setup this core backend
  51. bool NavEKF2_core::setup_core(uint8_t _imu_index, uint8_t _core_index)
  52. {
  53. imu_index = _imu_index;
  54. gyro_index_active = _imu_index;
  55. accel_index_active = _imu_index;
  56. core_index = _core_index;
  57. _ahrs = frontend->_ahrs;
  58. /*
  59. the imu_buffer_length needs to cope with a 260ms delay at a
  60. maximum fusion rate of 100Hz. Non-imu data coming in at faster
  61. than 100Hz is downsampled. For 50Hz main loop rate we need a
  62. shorter buffer.
  63. */
  64. if (AP::ins().get_sample_rate() < 100) {
  65. imu_buffer_length = 13;
  66. } else {
  67. // maximum 260 msec delay at 100 Hz fusion rate
  68. imu_buffer_length = 26;
  69. }
  70. if(!storedGPS.init(OBS_BUFFER_LENGTH)) {
  71. return false;
  72. }
  73. if(!storedMag.init(OBS_BUFFER_LENGTH)) {
  74. return false;
  75. }
  76. if(!storedBaro.init(OBS_BUFFER_LENGTH)) {
  77. return false;
  78. }
  79. if(!storedTAS.init(OBS_BUFFER_LENGTH)) {
  80. return false;
  81. }
  82. if(!storedOF.init(FLOW_BUFFER_LENGTH)) {
  83. return false;
  84. }
  85. // Note: the use of dual range finders potentially doubles the amount of to be stored
  86. if(!storedRange.init(2*OBS_BUFFER_LENGTH)) {
  87. return false;
  88. }
  89. // Note: range beacon data is read one beacon at a time and can arrive at a high rate
  90. if(!storedRangeBeacon.init(imu_buffer_length)) {
  91. return false;
  92. }
  93. if(!storedExtNav.init(OBS_BUFFER_LENGTH)) {
  94. return false;
  95. }
  96. if(!storedIMU.init(imu_buffer_length)) {
  97. return false;
  98. }
  99. if(!storedOutput.init(imu_buffer_length)) {
  100. return false;
  101. }
  102. return true;
  103. }
  104. /********************************************************
  105. * INIT FUNCTIONS *
  106. ********************************************************/
  107. // Use a function call rather than a constructor to initialise variables because it enables the filter to be re-started in flight if necessary.
  108. void NavEKF2_core::InitialiseVariables()
  109. {
  110. // calculate the nominal filter update rate
  111. const AP_InertialSensor &ins = AP::ins();
  112. localFilterTimeStep_ms = (uint8_t)(1000*ins.get_loop_delta_t());
  113. localFilterTimeStep_ms = MAX(localFilterTimeStep_ms,10);
  114. // initialise time stamps
  115. imuSampleTime_ms = frontend->imuSampleTime_us / 1000;
  116. prevTasStep_ms = imuSampleTime_ms;
  117. prevBetaStep_ms = imuSampleTime_ms;
  118. lastBaroReceived_ms = imuSampleTime_ms;
  119. lastVelPassTime_ms = 0;
  120. lastPosPassTime_ms = 0;
  121. lastHgtPassTime_ms = 0;
  122. lastTasPassTime_ms = 0;
  123. lastYawTime_ms = imuSampleTime_ms;
  124. lastTimeGpsReceived_ms = 0;
  125. secondLastGpsTime_ms = 0;
  126. lastDecayTime_ms = imuSampleTime_ms;
  127. timeAtLastAuxEKF_ms = imuSampleTime_ms;
  128. flowValidMeaTime_ms = imuSampleTime_ms;
  129. rngValidMeaTime_ms = imuSampleTime_ms;
  130. flowMeaTime_ms = 0;
  131. prevFlowFuseTime_ms = 0;
  132. gndHgtValidTime_ms = 0;
  133. ekfStartTime_ms = imuSampleTime_ms;
  134. lastGpsVelFail_ms = 0;
  135. lastGpsVelPass_ms = 0;
  136. lastGpsAidBadTime_ms = 0;
  137. timeTasReceived_ms = 0;
  138. lastPreAlignGpsCheckTime_ms = imuSampleTime_ms;
  139. lastPosReset_ms = 0;
  140. lastVelReset_ms = 0;
  141. lastPosResetD_ms = 0;
  142. lastRngMeasTime_ms = 0;
  143. terrainHgtStableSet_ms = 0;
  144. // initialise other variables
  145. gpsNoiseScaler = 1.0f;
  146. hgtTimeout = true;
  147. tasTimeout = true;
  148. badIMUdata = false;
  149. dtIMUavg = 0.0025f;
  150. dtEkfAvg = EKF_TARGET_DT;
  151. dt = 0;
  152. velDotNEDfilt.zero();
  153. lastKnownPositionNE.zero();
  154. prevTnb.zero();
  155. memset(&P[0][0], 0, sizeof(P));
  156. memset(&KH[0][0], 0, sizeof(KH));
  157. memset(&KHP[0][0], 0, sizeof(KHP));
  158. memset(&nextP[0][0], 0, sizeof(nextP));
  159. flowDataValid = false;
  160. rangeDataToFuse = false;
  161. Popt = 0.0f;
  162. terrainState = 0.0f;
  163. prevPosN = stateStruct.position.x;
  164. prevPosE = stateStruct.position.y;
  165. inhibitGndState = false;
  166. flowGyroBias.x = 0;
  167. flowGyroBias.y = 0;
  168. heldVelNE.zero();
  169. PV_AidingMode = AID_NONE;
  170. PV_AidingModePrev = AID_NONE;
  171. posTimeout = true;
  172. velTimeout = true;
  173. memset(&faultStatus, 0, sizeof(faultStatus));
  174. hgtRate = 0.0f;
  175. mag_state.q0 = 1;
  176. mag_state.DCM.identity();
  177. onGround = true;
  178. prevOnGround = true;
  179. inFlight = false;
  180. prevInFlight = false;
  181. manoeuvring = false;
  182. inhibitWindStates = true;
  183. gndOffsetValid = false;
  184. validOrigin = false;
  185. takeoffExpectedSet_ms = 0;
  186. expectGndEffectTakeoff = false;
  187. touchdownExpectedSet_ms = 0;
  188. expectGndEffectTouchdown = false;
  189. gpsSpdAccuracy = 0.0f;
  190. gpsPosAccuracy = 0.0f;
  191. gpsHgtAccuracy = 0.0f;
  192. baroHgtOffset = 0.0f;
  193. yawResetAngle = 0.0f;
  194. lastYawReset_ms = 0;
  195. tiltErrFilt = 1.0f;
  196. tiltAlignComplete = false;
  197. stateIndexLim = 23;
  198. baroStoreIndex = 0;
  199. rangeStoreIndex = 0;
  200. magStoreIndex = 0;
  201. gpsStoreIndex = 0;
  202. tasStoreIndex = 0;
  203. ofStoreIndex = 0;
  204. delAngCorrection.zero();
  205. velErrintegral.zero();
  206. posErrintegral.zero();
  207. gpsGoodToAlign = false;
  208. gpsNotAvailable = true;
  209. motorsArmed = false;
  210. prevMotorsArmed = false;
  211. innovationIncrement = 0;
  212. lastInnovation = 0;
  213. memset(&gpsCheckStatus, 0, sizeof(gpsCheckStatus));
  214. gpsSpdAccPass = false;
  215. ekfInnovationsPass = false;
  216. sAccFilterState1 = 0.0f;
  217. sAccFilterState2 = 0.0f;
  218. lastGpsCheckTime_ms = 0;
  219. lastInnovPassTime_ms = 0;
  220. lastInnovFailTime_ms = 0;
  221. gpsAccuracyGood = false;
  222. gpsloc_prev = {};
  223. gpsDriftNE = 0.0f;
  224. gpsVertVelFilt = 0.0f;
  225. gpsHorizVelFilt = 0.0f;
  226. memset(&statesArray, 0, sizeof(statesArray));
  227. posDownDerivative = 0.0f;
  228. posDown = 0.0f;
  229. posVelFusionDelayed = false;
  230. optFlowFusionDelayed = false;
  231. airSpdFusionDelayed = false;
  232. sideSlipFusionDelayed = false;
  233. posResetNE.zero();
  234. velResetNE.zero();
  235. posResetD = 0.0f;
  236. hgtInnovFiltState = 0.0f;
  237. imuDataDownSampledNew.delAng.zero();
  238. imuDataDownSampledNew.delVel.zero();
  239. imuDataDownSampledNew.delAngDT = 0.0f;
  240. imuDataDownSampledNew.delVelDT = 0.0f;
  241. runUpdates = false;
  242. framesSincePredict = 0;
  243. gpsYawResetRequest = false;
  244. quatAtLastMagReset = stateStruct.quat;
  245. delAngBiasLearned = false;
  246. memset(&filterStatus, 0, sizeof(filterStatus));
  247. gpsInhibit = false;
  248. activeHgtSource = 0;
  249. memset(&rngMeasIndex, 0, sizeof(rngMeasIndex));
  250. memset(&storedRngMeasTime_ms, 0, sizeof(storedRngMeasTime_ms));
  251. memset(&storedRngMeas, 0, sizeof(storedRngMeas));
  252. terrainHgtStable = true;
  253. ekfOriginHgtVar = 0.0f;
  254. ekfGpsRefHgt = 0.0;
  255. velOffsetNED.zero();
  256. posOffsetNED.zero();
  257. memset(&velPosObs, 0, sizeof(velPosObs));
  258. // range beacon fusion variables
  259. memset((void *)&rngBcnDataNew, 0, sizeof(rngBcnDataNew));
  260. memset((void *)&rngBcnDataDelayed, 0, sizeof(rngBcnDataDelayed));
  261. rngBcnStoreIndex = 0;
  262. lastRngBcnPassTime_ms = 0;
  263. rngBcnTestRatio = 0.0f;
  264. rngBcnHealth = false;
  265. rngBcnTimeout = true;
  266. varInnovRngBcn = 0.0f;
  267. innovRngBcn = 0.0f;
  268. memset(&lastTimeRngBcn_ms, 0, sizeof(lastTimeRngBcn_ms));
  269. rngBcnDataToFuse = false;
  270. beaconVehiclePosNED.zero();
  271. beaconVehiclePosErr = 1.0f;
  272. rngBcnLast3DmeasTime_ms = 0;
  273. rngBcnGoodToAlign = false;
  274. lastRngBcnChecked = 0;
  275. receiverPos.zero();
  276. memset(&receiverPosCov, 0, sizeof(receiverPosCov));
  277. rngBcnAlignmentStarted = false;
  278. rngBcnAlignmentCompleted = false;
  279. lastBeaconIndex = 0;
  280. rngBcnPosSum.zero();
  281. numBcnMeas = 0;
  282. rngSum = 0.0f;
  283. N_beacons = 0;
  284. maxBcnPosD = 0.0f;
  285. minBcnPosD = 0.0f;
  286. bcnPosOffset = 0.0f;
  287. bcnPosOffsetMax = 0.0f;
  288. bcnPosOffsetMaxVar = 0.0f;
  289. OffsetMaxInnovFilt = 0.0f;
  290. bcnPosOffsetMin = 0.0f;
  291. bcnPosOffsetMinVar = 0.0f;
  292. OffsetMinInnovFilt = 0.0f;
  293. rngBcnFuseDataReportIndex = 0;
  294. memset(&rngBcnFusionReport, 0, sizeof(rngBcnFusionReport));
  295. last_gps_idx = 0;
  296. // external nav data fusion
  297. memset((void *)&extNavDataNew, 0, sizeof(extNavDataNew));
  298. memset((void *)&extNavDataDelayed, 0, sizeof(extNavDataDelayed));
  299. extNavDataToFuse = false;
  300. extNavMeasTime_ms = 0;
  301. extNavLastPosResetTime_ms = 0;
  302. extNavUsedForYaw = false;
  303. extNavUsedForPos = false;
  304. extNavYawResetRequest = false;
  305. // zero data buffers
  306. storedIMU.reset();
  307. storedGPS.reset();
  308. storedBaro.reset();
  309. storedTAS.reset();
  310. storedRange.reset();
  311. storedOutput.reset();
  312. storedRangeBeacon.reset();
  313. storedExtNav.reset();
  314. // now init mag variables
  315. yawAlignComplete = false;
  316. have_table_earth_field = false;
  317. InitialiseVariablesMag();
  318. }
  319. /*
  320. separate out the mag reset so it can be used when compass learning completes
  321. */
  322. void NavEKF2_core::InitialiseVariablesMag()
  323. {
  324. lastHealthyMagTime_ms = imuSampleTime_ms;
  325. lastMagUpdate_us = 0;
  326. magYawResetTimer_ms = imuSampleTime_ms;
  327. magTimeout = false;
  328. allMagSensorsFailed = false;
  329. badMagYaw = false;
  330. finalInflightYawInit = false;
  331. finalInflightMagInit = false;
  332. inhibitMagStates = true;
  333. if (_ahrs->get_compass()) {
  334. magSelectIndex = _ahrs->get_compass()->get_primary();
  335. }
  336. lastMagOffsetsValid = false;
  337. magStateResetRequest = false;
  338. magStateInitComplete = false;
  339. magYawResetRequest = false;
  340. posDownAtLastMagReset = stateStruct.position.z;
  341. yawInnovAtLastMagReset = 0.0f;
  342. magFieldLearned = false;
  343. storedMag.reset();
  344. }
  345. // Initialise the states from accelerometer and magnetometer data (if present)
  346. // This method can only be used when the vehicle is static
  347. bool NavEKF2_core::InitialiseFilterBootstrap(void)
  348. {
  349. // If we are a plane and don't have GPS lock then don't initialise
  350. if (assume_zero_sideslip() && AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
  351. hal.util->snprintf(prearm_fail_string,
  352. sizeof(prearm_fail_string),
  353. "EKF2 init failure: No GPS lock");
  354. statesInitialised = false;
  355. return false;
  356. }
  357. if (statesInitialised) {
  358. // we are initialised, but we don't return true until the IMU
  359. // buffer has been filled. This prevents a timing
  360. // vulnerability with a pause in IMU data during filter startup
  361. readIMUData();
  362. readMagData();
  363. readGpsData();
  364. readBaroData();
  365. return storedIMU.is_filled();
  366. }
  367. // set re-used variables to zero
  368. InitialiseVariables();
  369. const AP_InertialSensor &ins = AP::ins();
  370. // Initialise IMU data
  371. dtIMUavg = ins.get_loop_delta_t();
  372. readIMUData();
  373. storedIMU.reset_history(imuDataNew);
  374. imuDataDelayed = imuDataNew;
  375. // acceleration vector in XYZ body axes measured by the IMU (m/s^2)
  376. Vector3f initAccVec;
  377. // TODO we should average accel readings over several cycles
  378. initAccVec = ins.get_accel(accel_index_active);
  379. // read the magnetometer data
  380. readMagData();
  381. // normalise the acceleration vector
  382. float pitch=0, roll=0;
  383. if (initAccVec.length() > 0.001f) {
  384. initAccVec.normalize();
  385. // calculate initial pitch angle
  386. pitch = asinf(initAccVec.x);
  387. // calculate initial roll angle
  388. roll = atan2f(-initAccVec.y , -initAccVec.z);
  389. }
  390. // calculate initial roll and pitch orientation
  391. stateStruct.quat.from_euler(roll, pitch, 0.0f);
  392. // initialise dynamic states
  393. stateStruct.velocity.zero();
  394. stateStruct.position.zero();
  395. stateStruct.angErr.zero();
  396. // initialise static process model states
  397. stateStruct.gyro_bias.zero();
  398. stateStruct.gyro_scale.x = 1.0f;
  399. stateStruct.gyro_scale.y = 1.0f;
  400. stateStruct.gyro_scale.z = 1.0f;
  401. stateStruct.accel_zbias = 0.0f;
  402. stateStruct.wind_vel.zero();
  403. stateStruct.earth_magfield.zero();
  404. stateStruct.body_magfield.zero();
  405. // read the GPS and set the position and velocity states
  406. readGpsData();
  407. ResetVelocity();
  408. ResetPosition();
  409. // read the barometer and set the height state
  410. readBaroData();
  411. ResetHeight();
  412. // define Earth rotation vector in the NED navigation frame
  413. calcEarthRateNED(earthRateNED, _ahrs->get_home().lat);
  414. // initialise the covariance matrix
  415. CovarianceInit();
  416. // reset output states
  417. StoreOutputReset();
  418. // set to true now that states have be initialised
  419. statesInitialised = true;
  420. // reset inactive biases
  421. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  422. inactiveBias[i].gyro_bias.zero();
  423. inactiveBias[i].accel_zbias = 0;
  424. inactiveBias[i].gyro_scale.x = 1;
  425. inactiveBias[i].gyro_scale.y = 1;
  426. inactiveBias[i].gyro_scale.z = 1;
  427. }
  428. // we initially return false to wait for the IMU buffer to fill
  429. return false;
  430. }
  431. // initialise the covariance matrix
  432. void NavEKF2_core::CovarianceInit()
  433. {
  434. // zero the matrix
  435. memset(&P[0][0], 0, sizeof(P));
  436. // attitude error
  437. P[0][0] = 0.1f;
  438. P[1][1] = 0.1f;
  439. P[2][2] = 0.1f;
  440. // velocities
  441. P[3][3] = sq(frontend->_gpsHorizVelNoise);
  442. P[4][4] = P[3][3];
  443. P[5][5] = sq(frontend->_gpsVertVelNoise);
  444. // positions
  445. P[6][6] = sq(frontend->_gpsHorizPosNoise);
  446. P[7][7] = P[6][6];
  447. P[8][8] = sq(frontend->_baroAltNoise);
  448. // gyro delta angle biases
  449. P[9][9] = sq(radians(InitialGyroBiasUncertainty() * dtEkfAvg));
  450. P[10][10] = P[9][9];
  451. P[11][11] = P[9][9];
  452. // gyro scale factor biases
  453. P[12][12] = sq(1e-3);
  454. P[13][13] = P[12][12];
  455. P[14][14] = P[12][12];
  456. // Z delta velocity bias
  457. P[15][15] = sq(INIT_ACCEL_BIAS_UNCERTAINTY * dtEkfAvg);
  458. // earth magnetic field
  459. P[16][16] = 0.0f;
  460. P[17][17] = P[16][16];
  461. P[18][18] = P[16][16];
  462. // body magnetic field
  463. P[19][19] = 0.0f;
  464. P[20][20] = P[19][19];
  465. P[21][21] = P[19][19];
  466. // wind velocities
  467. P[22][22] = 0.0f;
  468. P[23][23] = P[22][22];
  469. // optical flow ground height covariance
  470. Popt = 0.25f;
  471. }
  472. /********************************************************
  473. * UPDATE FUNCTIONS *
  474. ********************************************************/
  475. // Update Filter States - this should be called whenever new IMU data is available
  476. void NavEKF2_core::UpdateFilter(bool predict)
  477. {
  478. // Set the flag to indicate to the filter that the front-end has given permission for a new state prediction cycle to be started
  479. startPredictEnabled = predict;
  480. // don't run filter updates if states have not been initialised
  481. if (!statesInitialised) {
  482. return;
  483. }
  484. // start the timer used for load measurement
  485. #if ENABLE_EKF_TIMING
  486. void *istate = hal.scheduler->disable_interrupts_save();
  487. static uint32_t timing_start_us;
  488. timing_start_us = AP_HAL::micros();
  489. #endif
  490. hal.util->perf_begin(_perf_UpdateFilter);
  491. fill_scratch_variables();
  492. // TODO - in-flight restart method
  493. //get starting time for update step
  494. imuSampleTime_ms = frontend->imuSampleTime_us / 1000;
  495. // Check arm status and perform required checks and mode changes
  496. controlFilterModes();
  497. // read IMU data as delta angles and velocities
  498. readIMUData();
  499. // Run the EKF equations to estimate at the fusion time horizon if new IMU data is available in the buffer
  500. if (runUpdates) {
  501. // Predict states using IMU data from the delayed time horizon
  502. UpdateStrapdownEquationsNED();
  503. // Predict the covariance growth
  504. CovariancePrediction();
  505. // Update states using magnetometer data
  506. SelectMagFusion();
  507. // Update states using GPS and altimeter data
  508. SelectVelPosFusion();
  509. // Update states using range beacon data
  510. SelectRngBcnFusion();
  511. // Update states using optical flow data
  512. SelectFlowFusion();
  513. // Update states using airspeed data
  514. SelectTasFusion();
  515. // Update states using sideslip constraint assumption for fly-forward vehicles
  516. SelectBetaFusion();
  517. // Update the filter status
  518. updateFilterStatus();
  519. }
  520. // Wind output forward from the fusion to output time horizon
  521. calcOutputStates();
  522. // stop the timer used for load measurement
  523. hal.util->perf_end(_perf_UpdateFilter);
  524. #if ENABLE_EKF_TIMING
  525. static uint32_t total_us;
  526. static uint32_t timing_counter;
  527. total_us += AP_HAL::micros() - timing_start_us;
  528. if (timing_counter++ == 4000) {
  529. hal.console->printf("ekf2 avg %.2f us\n", total_us / float(timing_counter));
  530. total_us = 0;
  531. timing_counter = 0;
  532. }
  533. hal.scheduler->restore_interrupts(istate);
  534. #endif
  535. /*
  536. this is a check to cope with a vehicle sitting idle on the
  537. ground and getting over-confident of the state. The symptoms
  538. would be "gyros still settling" when the user tries to arm. In
  539. that state the EKF can't recover, so we do a hard reset and let
  540. it try again.
  541. */
  542. if (filterStatus.value != 0) {
  543. last_filter_ok_ms = AP_HAL::millis();
  544. }
  545. if (filterStatus.value == 0 &&
  546. last_filter_ok_ms != 0 &&
  547. AP_HAL::millis() - last_filter_ok_ms > 5000 &&
  548. !hal.util->get_soft_armed()) {
  549. // we've been unhealthy for 5 seconds after being healthy, reset the filter
  550. gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u forced reset",(unsigned)imu_index);
  551. last_filter_ok_ms = 0;
  552. statesInitialised = false;
  553. InitialiseFilterBootstrap();
  554. }
  555. }
  556. void NavEKF2_core::correctDeltaAngle(Vector3f &delAng, float delAngDT, uint8_t gyro_index)
  557. {
  558. delAng.x = delAng.x * stateStruct.gyro_scale.x;
  559. delAng.y = delAng.y * stateStruct.gyro_scale.y;
  560. delAng.z = delAng.z * stateStruct.gyro_scale.z;
  561. delAng -= inactiveBias[gyro_index].gyro_bias * (delAngDT / dtEkfAvg);
  562. }
  563. void NavEKF2_core::correctDeltaVelocity(Vector3f &delVel, float delVelDT, uint8_t accel_index)
  564. {
  565. delVel.z -= inactiveBias[accel_index].accel_zbias * (delVelDT / dtEkfAvg);
  566. }
  567. /*
  568. * Update the quaternion, velocity and position states using delayed IMU measurements
  569. * because the EKF is running on a delayed time horizon. Note that the quaternion is
  570. * not used by the EKF equations, which instead estimate the error in the attitude of
  571. * the vehicle when each observation is fused. This attitude error is then used to correct
  572. * the quaternion.
  573. */
  574. void NavEKF2_core::UpdateStrapdownEquationsNED()
  575. {
  576. // update the quaternion states by rotating from the previous attitude through
  577. // the delta angle rotation quaternion and normalise
  578. // apply correction for earth's rotation rate
  579. // % * - and + operators have been overloaded
  580. stateStruct.quat.rotate(delAngCorrected - prevTnb * earthRateNED*imuDataDelayed.delAngDT);
  581. stateStruct.quat.normalize();
  582. // transform body delta velocities to delta velocities in the nav frame
  583. // use the nav frame from previous time step as the delta velocities
  584. // have been rotated into that frame
  585. // * and + operators have been overloaded
  586. Vector3f delVelNav; // delta velocity vector in earth axes
  587. delVelNav = prevTnb.mul_transpose(delVelCorrected);
  588. delVelNav.z += GRAVITY_MSS*imuDataDelayed.delVelDT;
  589. // calculate the body to nav cosine matrix
  590. stateStruct.quat.inverse().rotation_matrix(prevTnb);
  591. // calculate the rate of change of velocity (used for launch detect and other functions)
  592. velDotNED = delVelNav / imuDataDelayed.delVelDT;
  593. // apply a first order lowpass filter
  594. velDotNEDfilt = velDotNED * 0.05f + velDotNEDfilt * 0.95f;
  595. // calculate a magnitude of the filtered nav acceleration (required for GPS
  596. // variance estimation)
  597. accNavMag = velDotNEDfilt.length();
  598. accNavMagHoriz = norm(velDotNEDfilt.x , velDotNEDfilt.y);
  599. // if we are not aiding, then limit the horizontal magnitude of acceleration
  600. // to prevent large manoeuvre transients disturbing the attitude
  601. if ((PV_AidingMode == AID_NONE) && (accNavMagHoriz > 5.0f)) {
  602. float gain = 5.0f/accNavMagHoriz;
  603. delVelNav.x *= gain;
  604. delVelNav.y *= gain;
  605. }
  606. // save velocity for use in trapezoidal integration for position calcuation
  607. Vector3f lastVelocity = stateStruct.velocity;
  608. // sum delta velocities to get velocity
  609. stateStruct.velocity += delVelNav;
  610. // apply a trapezoidal integration to velocities to calculate position
  611. stateStruct.position += (stateStruct.velocity + lastVelocity) * (imuDataDelayed.delVelDT*0.5f);
  612. // accumulate the bias delta angle and time since last reset by an OF measurement arrival
  613. delAngBodyOF += delAngCorrected;
  614. delTimeOF += imuDataDelayed.delAngDT;
  615. // limit states to protect against divergence
  616. ConstrainStates();
  617. }
  618. /*
  619. * Propagate PVA solution forward from the fusion time horizon to the current time horizon
  620. * using simple observer which performs two functions:
  621. * 1) Corrects for the delayed time horizon used by the EKF.
  622. * 2) Applies a LPF to state corrections to prevent 'stepping' in states due to measurement
  623. * fusion introducing unwanted noise into the control loops.
  624. * The inspiration for using a complementary filter to correct for time delays in the EKF
  625. * is based on the work by A Khosravian.
  626. *
  627. * "Recursive Attitude Estimation in the Presence of Multi-rate and Multi-delay Vector Measurements"
  628. * A Khosravian, J Trumpf, R Mahony, T Hamel, Australian National University
  629. */
  630. void NavEKF2_core::calcOutputStates()
  631. {
  632. // apply corrections to the IMU data
  633. Vector3f delAngNewCorrected = imuDataNew.delAng;
  634. Vector3f delVelNewCorrected = imuDataNew.delVel;
  635. correctDeltaAngle(delAngNewCorrected, imuDataNew.delAngDT, imuDataNew.gyro_index);
  636. correctDeltaVelocity(delVelNewCorrected, imuDataNew.delVelDT, imuDataNew.accel_index);
  637. // apply corections to track EKF solution
  638. Vector3f delAng = delAngNewCorrected + delAngCorrection;
  639. // convert the rotation vector to its equivalent quaternion
  640. Quaternion deltaQuat;
  641. deltaQuat.from_axis_angle(delAng);
  642. // update the quaternion states by rotating from the previous attitude through
  643. // the delta angle rotation quaternion and normalise
  644. outputDataNew.quat *= deltaQuat;
  645. outputDataNew.quat.normalize();
  646. // calculate the body to nav cosine matrix
  647. Matrix3f Tbn_temp;
  648. outputDataNew.quat.rotation_matrix(Tbn_temp);
  649. // transform body delta velocities to delta velocities in the nav frame
  650. Vector3f delVelNav = Tbn_temp*delVelNewCorrected;
  651. delVelNav.z += GRAVITY_MSS*imuDataNew.delVelDT;
  652. // save velocity for use in trapezoidal integration for position calcuation
  653. Vector3f lastVelocity = outputDataNew.velocity;
  654. // sum delta velocities to get velocity
  655. outputDataNew.velocity += delVelNav;
  656. // apply a trapezoidal integration to velocities to calculate position
  657. outputDataNew.position += (outputDataNew.velocity + lastVelocity) * (imuDataNew.delVelDT*0.5f);
  658. // If the IMU accelerometer is offset from the body frame origin, then calculate corrections
  659. // that can be added to the EKF velocity and position outputs so that they represent the velocity
  660. // and position of the body frame origin.
  661. // Note the * operator has been overloaded to operate as a dot product
  662. if (!accelPosOffset.is_zero()) {
  663. // calculate the average angular rate across the last IMU update
  664. // note delAngDT is prevented from being zero in readIMUData()
  665. Vector3f angRate = imuDataNew.delAng * (1.0f/imuDataNew.delAngDT);
  666. // Calculate the velocity of the body frame origin relative to the IMU in body frame
  667. // and rotate into earth frame. Note % operator has been overloaded to perform a cross product
  668. Vector3f velBodyRelIMU = angRate % (- accelPosOffset);
  669. velOffsetNED = Tbn_temp * velBodyRelIMU;
  670. // calculate the earth frame position of the body frame origin relative to the IMU
  671. posOffsetNED = Tbn_temp * (- accelPosOffset);
  672. } else {
  673. velOffsetNED.zero();
  674. posOffsetNED.zero();
  675. }
  676. // store INS states in a ring buffer that with the same length and time coordinates as the IMU data buffer
  677. if (runUpdates) {
  678. // store the states at the output time horizon
  679. storedOutput[storedIMU.get_youngest_index()] = outputDataNew;
  680. // recall the states from the fusion time horizon
  681. outputDataDelayed = storedOutput[storedIMU.get_oldest_index()];
  682. // compare quaternion data with EKF quaternion at the fusion time horizon and calculate correction
  683. // divide the demanded quaternion by the estimated to get the error
  684. Quaternion quatErr = stateStruct.quat / outputDataDelayed.quat;
  685. // Convert to a delta rotation using a small angle approximation
  686. quatErr.normalize();
  687. Vector3f deltaAngErr;
  688. float scaler;
  689. if (quatErr[0] >= 0.0f) {
  690. scaler = 2.0f;
  691. } else {
  692. scaler = -2.0f;
  693. }
  694. deltaAngErr.x = scaler * quatErr[1];
  695. deltaAngErr.y = scaler * quatErr[2];
  696. deltaAngErr.z = scaler * quatErr[3];
  697. // calculate a gain that provides tight tracking of the estimator states and
  698. // adjust for changes in time delay to maintain consistent damping ratio of ~0.7
  699. float timeDelay = 1e-3f * (float)(imuDataNew.time_ms - imuDataDelayed.time_ms);
  700. timeDelay = fmaxf(timeDelay, dtIMUavg);
  701. float errorGain = 0.5f / timeDelay;
  702. // calculate a corrrection to the delta angle
  703. // that will cause the INS to track the EKF quaternions
  704. delAngCorrection = deltaAngErr * errorGain * dtIMUavg;
  705. // calculate velocity and position tracking errors
  706. Vector3f velErr = (stateStruct.velocity - outputDataDelayed.velocity);
  707. Vector3f posErr = (stateStruct.position - outputDataDelayed.position);
  708. // collect magnitude tracking error for diagnostics
  709. outputTrackError.x = deltaAngErr.length();
  710. outputTrackError.y = velErr.length();
  711. outputTrackError.z = posErr.length();
  712. // convert user specified time constant from centi-seconds to seconds
  713. float tauPosVel = constrain_float(0.01f*(float)frontend->_tauVelPosOutput, 0.1f, 0.5f);
  714. // calculate a gain to track the EKF position states with the specified time constant
  715. float velPosGain = dtEkfAvg / constrain_float(tauPosVel, dtEkfAvg, 10.0f);
  716. // use a PI feedback to calculate a correction that will be applied to the output state history
  717. posErrintegral += posErr;
  718. velErrintegral += velErr;
  719. Vector3f velCorrection = velErr * velPosGain + velErrintegral * sq(velPosGain) * 0.1f;
  720. Vector3f posCorrection = posErr * velPosGain + posErrintegral * sq(velPosGain) * 0.1f;
  721. // loop through the output filter state history and apply the corrections to the velocity and position states
  722. // this method is too expensive to use for the attitude states due to the quaternion operations required
  723. // but does not introduce a time delay in the 'correction loop' and allows smaller tracking time constants
  724. // to be used
  725. output_elements outputStates;
  726. for (unsigned index=0; index < imu_buffer_length; index++) {
  727. outputStates = storedOutput[index];
  728. // a constant velocity correction is applied
  729. outputStates.velocity += velCorrection;
  730. // a constant position correction is applied
  731. outputStates.position += posCorrection;
  732. // push the updated data to the buffer
  733. storedOutput[index] = outputStates;
  734. }
  735. // update output state to corrected values
  736. outputDataNew = storedOutput[storedIMU.get_youngest_index()];
  737. }
  738. }
  739. /*
  740. * Calculate the predicted state covariance matrix using algebraic equations generated with Matlab symbolic toolbox.
  741. * The script file used to generate these and other equations in this filter can be found here:
  742. * https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
  743. */
  744. void NavEKF2_core::CovariancePrediction()
  745. {
  746. hal.util->perf_begin(_perf_CovariancePrediction);
  747. float windVelSigma; // wind velocity 1-sigma process noise - m/s
  748. float dAngBiasSigma;// delta angle bias 1-sigma process noise - rad/s
  749. float dVelBiasSigma;// delta velocity bias 1-sigma process noise - m/s
  750. float dAngScaleSigma;// delta angle scale factor 1-Sigma process noise
  751. float magEarthSigma;// earth magnetic field 1-sigma process noise
  752. float magBodySigma; // body magnetic field 1-sigma process noise
  753. float daxNoise; // X axis delta angle noise variance rad^2
  754. float dayNoise; // Y axis delta angle noise variance rad^2
  755. float dazNoise; // Z axis delta angle noise variance rad^2
  756. float dvxNoise; // X axis delta velocity variance noise (m/s)^2
  757. float dvyNoise; // Y axis delta velocity variance noise (m/s)^2
  758. float dvzNoise; // Z axis delta velocity variance noise (m/s)^2
  759. float dvx; // X axis delta velocity (m/s)
  760. float dvy; // Y axis delta velocity (m/s)
  761. float dvz; // Z axis delta velocity (m/s)
  762. float dax; // X axis delta angle (rad)
  763. float day; // Y axis delta angle (rad)
  764. float daz; // Z axis delta angle (rad)
  765. float q0; // attitude quaternion
  766. float q1; // attitude quaternion
  767. float q2; // attitude quaternion
  768. float q3; // attitude quaternion
  769. float dax_b; // X axis delta angle measurement bias (rad)
  770. float day_b; // Y axis delta angle measurement bias (rad)
  771. float daz_b; // Z axis delta angle measurement bias (rad)
  772. float dax_s; // X axis delta angle measurement scale factor
  773. float day_s; // Y axis delta angle measurement scale factor
  774. float daz_s; // Z axis delta angle measurement scale factor
  775. float dvz_b; // Z axis delta velocity measurement bias (rad)
  776. Vector25 SF;
  777. Vector5 SG;
  778. Vector8 SQ;
  779. Vector24 processNoise;
  780. // calculate covariance prediction process noise
  781. // use filtered height rate to increase wind process noise when climbing or descending
  782. // this allows for wind gradient effects.
  783. // filter height rate using a 10 second time constant filter
  784. dt = imuDataDelayed.delAngDT;
  785. float alpha = 0.1f * dt;
  786. hgtRate = hgtRate * (1.0f - alpha) - stateStruct.velocity.z * alpha;
  787. // use filtered height rate to increase wind process noise when climbing or descending
  788. // this allows for wind gradient effects.
  789. windVelSigma = dt * constrain_float(frontend->_windVelProcessNoise, 0.0f, 1.0f) * (1.0f + constrain_float(frontend->_wndVarHgtRateScale, 0.0f, 1.0f) * fabsf(hgtRate));
  790. dAngBiasSigma = sq(dt) * constrain_float(frontend->_gyroBiasProcessNoise, 0.0f, 1.0f);
  791. dVelBiasSigma = sq(dt) * constrain_float(frontend->_accelBiasProcessNoise, 0.0f, 1.0f);
  792. dAngScaleSigma = dt * constrain_float(frontend->_gyroScaleProcessNoise, 0.0f, 1.0f);
  793. magEarthSigma = dt * constrain_float(frontend->_magEarthProcessNoise, 0.0f, 1.0f);
  794. magBodySigma = dt * constrain_float(frontend->_magBodyProcessNoise, 0.0f, 1.0f);
  795. for (uint8_t i= 0; i<=8; i++) processNoise[i] = 0.0f;
  796. for (uint8_t i=9; i<=11; i++) processNoise[i] = dAngBiasSigma;
  797. for (uint8_t i=12; i<=14; i++) processNoise[i] = dAngScaleSigma;
  798. if (expectGndEffectTakeoff) {
  799. processNoise[15] = 0.0f;
  800. } else {
  801. processNoise[15] = dVelBiasSigma;
  802. }
  803. for (uint8_t i=16; i<=18; i++) processNoise[i] = magEarthSigma;
  804. for (uint8_t i=19; i<=21; i++) processNoise[i] = magBodySigma;
  805. for (uint8_t i=22; i<=23; i++) processNoise[i] = windVelSigma;
  806. for (uint8_t i= 0; i<=stateIndexLim; i++) processNoise[i] = sq(processNoise[i]);
  807. // set variables used to calculate covariance growth
  808. dvx = imuDataDelayed.delVel.x;
  809. dvy = imuDataDelayed.delVel.y;
  810. dvz = imuDataDelayed.delVel.z;
  811. dax = imuDataDelayed.delAng.x;
  812. day = imuDataDelayed.delAng.y;
  813. daz = imuDataDelayed.delAng.z;
  814. q0 = stateStruct.quat[0];
  815. q1 = stateStruct.quat[1];
  816. q2 = stateStruct.quat[2];
  817. q3 = stateStruct.quat[3];
  818. dax_b = stateStruct.gyro_bias.x;
  819. day_b = stateStruct.gyro_bias.y;
  820. daz_b = stateStruct.gyro_bias.z;
  821. dax_s = stateStruct.gyro_scale.x;
  822. day_s = stateStruct.gyro_scale.y;
  823. daz_s = stateStruct.gyro_scale.z;
  824. dvz_b = stateStruct.accel_zbias;
  825. float _gyrNoise = constrain_float(frontend->_gyrNoise, 0.0f, 1.0f);
  826. daxNoise = dayNoise = dazNoise = sq(dt*_gyrNoise);
  827. float _accNoise = constrain_float(frontend->_accNoise, 0.0f, 10.0f);
  828. dvxNoise = dvyNoise = dvzNoise = sq(dt*_accNoise);
  829. // calculate the predicted covariance due to inertial sensor error propagation
  830. // we calculate the upper diagonal and copy to take advantage of symmetry
  831. SF[0] = daz_b/2 - (daz*daz_s)/2;
  832. SF[1] = day_b/2 - (day*day_s)/2;
  833. SF[2] = dax_b/2 - (dax*dax_s)/2;
  834. SF[3] = q3/2 - (q0*SF[0])/2 + (q1*SF[1])/2 - (q2*SF[2])/2;
  835. SF[4] = q0/2 - (q1*SF[2])/2 - (q2*SF[1])/2 + (q3*SF[0])/2;
  836. SF[5] = q1/2 + (q0*SF[2])/2 - (q2*SF[0])/2 - (q3*SF[1])/2;
  837. SF[6] = q3/2 + (q0*SF[0])/2 - (q1*SF[1])/2 - (q2*SF[2])/2;
  838. SF[7] = q0/2 - (q1*SF[2])/2 + (q2*SF[1])/2 - (q3*SF[0])/2;
  839. SF[8] = q0/2 + (q1*SF[2])/2 - (q2*SF[1])/2 - (q3*SF[0])/2;
  840. SF[9] = q2/2 + (q0*SF[1])/2 + (q1*SF[0])/2 + (q3*SF[2])/2;
  841. SF[10] = q2/2 - (q0*SF[1])/2 - (q1*SF[0])/2 + (q3*SF[2])/2;
  842. SF[11] = q2/2 + (q0*SF[1])/2 - (q1*SF[0])/2 - (q3*SF[2])/2;
  843. SF[12] = q1/2 + (q0*SF[2])/2 + (q2*SF[0])/2 + (q3*SF[1])/2;
  844. SF[13] = q1/2 - (q0*SF[2])/2 + (q2*SF[0])/2 - (q3*SF[1])/2;
  845. SF[14] = q3/2 + (q0*SF[0])/2 + (q1*SF[1])/2 + (q2*SF[2])/2;
  846. SF[15] = - sq(q0) - sq(q1) - sq(q2) - sq(q3);
  847. SF[16] = dvz_b - dvz;
  848. SF[17] = dvx;
  849. SF[18] = dvy;
  850. SF[19] = sq(q2);
  851. SF[20] = SF[19] - sq(q0) + sq(q1) - sq(q3);
  852. SF[21] = SF[19] + sq(q0) - sq(q1) - sq(q3);
  853. SF[22] = 2*q0*q1 - 2*q2*q3;
  854. SF[23] = SF[19] - sq(q0) - sq(q1) + sq(q3);
  855. SF[24] = 2*q1*q2;
  856. SG[0] = - sq(q0) - sq(q1) - sq(q2) - sq(q3);
  857. SG[1] = sq(q3);
  858. SG[2] = sq(q2);
  859. SG[3] = sq(q1);
  860. SG[4] = sq(q0);
  861. SQ[0] = - dvyNoise*(2*q0*q1 + 2*q2*q3)*(SG[1] - SG[2] + SG[3] - SG[4]) - dvzNoise*(2*q0*q1 - 2*q2*q3)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvxNoise*(2*q0*q2 - 2*q1*q3)*(2*q0*q3 + 2*q1*q2);
  862. SQ[1] = dvxNoise*(2*q0*q2 - 2*q1*q3)*(SG[1] + SG[2] - SG[3] - SG[4]) + dvzNoise*(2*q0*q2 + 2*q1*q3)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvyNoise*(2*q0*q1 + 2*q2*q3)*(2*q0*q3 - 2*q1*q2);
  863. SQ[2] = dvyNoise*(2*q0*q3 - 2*q1*q2)*(SG[1] - SG[2] + SG[3] - SG[4]) - dvxNoise*(2*q0*q3 + 2*q1*q2)*(SG[1] + SG[2] - SG[3] - SG[4]) - dvzNoise*(2*q0*q1 - 2*q2*q3)*(2*q0*q2 + 2*q1*q3);
  864. SQ[3] = sq(SG[0]);
  865. SQ[4] = 2*q2*q3;
  866. SQ[5] = 2*q1*q3;
  867. SQ[6] = 2*q1*q2;
  868. SQ[7] = SG[4];
  869. Vector23 SPP;
  870. SPP[0] = SF[17]*(2*q0*q1 + 2*q2*q3) + SF[18]*(2*q0*q2 - 2*q1*q3);
  871. SPP[1] = SF[18]*(2*q0*q2 + 2*q1*q3) + SF[16]*(SF[24] - 2*q0*q3);
  872. SPP[2] = 2*q3*SF[8] + 2*q1*SF[11] - 2*q0*SF[14] - 2*q2*SF[13];
  873. SPP[3] = 2*q1*SF[7] + 2*q2*SF[6] - 2*q0*SF[12] - 2*q3*SF[10];
  874. SPP[4] = 2*q0*SF[6] - 2*q3*SF[7] - 2*q1*SF[10] + 2*q2*SF[12];
  875. SPP[5] = 2*q0*SF[8] + 2*q2*SF[11] + 2*q1*SF[13] + 2*q3*SF[14];
  876. SPP[6] = 2*q0*SF[7] + 2*q3*SF[6] + 2*q2*SF[10] + 2*q1*SF[12];
  877. SPP[7] = SF[18]*SF[20] - SF[16]*(2*q0*q1 + 2*q2*q3);
  878. SPP[8] = 2*q1*SF[3] - 2*q2*SF[4] - 2*q3*SF[5] + 2*q0*SF[9];
  879. SPP[9] = 2*q0*SF[5] - 2*q1*SF[4] - 2*q2*SF[3] + 2*q3*SF[9];
  880. SPP[10] = SF[17]*SF[20] + SF[16]*(2*q0*q2 - 2*q1*q3);
  881. SPP[11] = SF[17]*SF[21] - SF[18]*(SF[24] + 2*q0*q3);
  882. SPP[12] = SF[17]*SF[22] - SF[16]*(SF[24] + 2*q0*q3);
  883. SPP[13] = 2*q0*SF[4] + 2*q1*SF[5] + 2*q3*SF[3] + 2*q2*SF[9];
  884. SPP[14] = 2*q2*SF[8] - 2*q0*SF[11] - 2*q1*SF[14] + 2*q3*SF[13];
  885. SPP[15] = SF[18]*SF[23] + SF[17]*(SF[24] - 2*q0*q3);
  886. SPP[16] = daz*SF[19] + daz*sq(q0) + daz*sq(q1) + daz*sq(q3);
  887. SPP[17] = day*SF[19] + day*sq(q0) + day*sq(q1) + day*sq(q3);
  888. SPP[18] = dax*SF[19] + dax*sq(q0) + dax*sq(q1) + dax*sq(q3);
  889. SPP[19] = SF[16]*SF[23] - SF[17]*(2*q0*q2 + 2*q1*q3);
  890. SPP[20] = SF[16]*SF[21] - SF[18]*SF[22];
  891. SPP[21] = 2*q0*q2 + 2*q1*q3;
  892. SPP[22] = SF[15];
  893. if (inhibitMagStates) {
  894. zeroRows(P,16,21);
  895. zeroCols(P,16,21);
  896. } else if (inhibitWindStates) {
  897. zeroRows(P,22,23);
  898. zeroCols(P,22,23);
  899. }
  900. nextP[0][0] = daxNoise*SQ[3] + SPP[5]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[9][0]*SPP[22] + P[12][0]*SPP[18] + P[2][0]*(2*q1*SF[3] - 2*q2*SF[4] - 2*q3*SF[5] + 2*q0*SF[9])) - SPP[4]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[9][1]*SPP[22] + P[12][1]*SPP[18] + P[2][1]*(2*q1*SF[3] - 2*q2*SF[4] - 2*q3*SF[5] + 2*q0*SF[9])) + SPP[8]*(P[0][2]*SPP[5] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18] - P[1][2]*(2*q0*SF[6] - 2*q3*SF[7] - 2*q1*SF[10] + 2*q2*SF[12])) + SPP[22]*(P[0][9]*SPP[5] - P[1][9]*SPP[4] + P[9][9]*SPP[22] + P[12][9]*SPP[18] + P[2][9]*(2*q1*SF[3] - 2*q2*SF[4] - 2*q3*SF[5] + 2*q0*SF[9])) + SPP[18]*(P[0][12]*SPP[5] - P[1][12]*SPP[4] + P[9][12]*SPP[22] + P[12][12]*SPP[18] + P[2][12]*(2*q1*SF[3] - 2*q2*SF[4] - 2*q3*SF[5] + 2*q0*SF[9]));
  901. nextP[0][1] = SPP[6]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[8] + P[9][1]*SPP[22] + P[12][1]*SPP[18]) - SPP[2]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[8] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) + SPP[22]*(P[0][10]*SPP[5] - P[1][10]*SPP[4] + P[2][10]*SPP[8] + P[9][10]*SPP[22] + P[12][10]*SPP[18]) + SPP[17]*(P[0][13]*SPP[5] - P[1][13]*SPP[4] + P[2][13]*SPP[8] + P[9][13]*SPP[22] + P[12][13]*SPP[18]) - (2*q0*SF[5] - 2*q1*SF[4] - 2*q2*SF[3] + 2*q3*SF[9])*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18]);
  902. nextP[1][1] = dayNoise*SQ[3] - SPP[2]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[9] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) + SPP[6]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[9] + P[10][1]*SPP[22] + P[13][1]*SPP[17]) - SPP[9]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[9] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) + SPP[22]*(P[1][10]*SPP[6] - P[0][10]*SPP[2] - P[2][10]*SPP[9] + P[10][10]*SPP[22] + P[13][10]*SPP[17]) + SPP[17]*(P[1][13]*SPP[6] - P[0][13]*SPP[2] - P[2][13]*SPP[9] + P[10][13]*SPP[22] + P[13][13]*SPP[17]);
  903. nextP[0][2] = SPP[13]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18]) - SPP[3]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[8] + P[9][1]*SPP[22] + P[12][1]*SPP[18]) + SPP[22]*(P[0][11]*SPP[5] - P[1][11]*SPP[4] + P[2][11]*SPP[8] + P[9][11]*SPP[22] + P[12][11]*SPP[18]) + SPP[16]*(P[0][14]*SPP[5] - P[1][14]*SPP[4] + P[2][14]*SPP[8] + P[9][14]*SPP[22] + P[12][14]*SPP[18]) + (2*q2*SF[8] - 2*q0*SF[11] - 2*q1*SF[14] + 2*q3*SF[13])*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[8] + P[9][0]*SPP[22] + P[12][0]*SPP[18]);
  904. nextP[1][2] = SPP[13]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[9] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) - SPP[3]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[9] + P[10][1]*SPP[22] + P[13][1]*SPP[17]) + SPP[22]*(P[1][11]*SPP[6] - P[0][11]*SPP[2] - P[2][11]*SPP[9] + P[10][11]*SPP[22] + P[13][11]*SPP[17]) + SPP[16]*(P[1][14]*SPP[6] - P[0][14]*SPP[2] - P[2][14]*SPP[9] + P[10][14]*SPP[22] + P[13][14]*SPP[17]) + (2*q2*SF[8] - 2*q0*SF[11] - 2*q1*SF[14] + 2*q3*SF[13])*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[9] + P[10][0]*SPP[22] + P[13][0]*SPP[17]);
  905. nextP[2][2] = dazNoise*SQ[3] - SPP[3]*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]) + SPP[14]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) + SPP[13]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]) + SPP[22]*(P[0][11]*SPP[14] - P[1][11]*SPP[3] + P[2][11]*SPP[13] + P[11][11]*SPP[22] + P[14][11]*SPP[16]) + SPP[16]*(P[0][14]*SPP[14] - P[1][14]*SPP[3] + P[2][14]*SPP[13] + P[11][14]*SPP[22] + P[14][14]*SPP[16]);
  906. nextP[0][3] = P[0][3]*SPP[5] - P[1][3]*SPP[4] + P[2][3]*SPP[8] + P[9][3]*SPP[22] + P[12][3]*SPP[18] + SPP[1]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[8] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) + SPP[15]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18]) - SPP[21]*(P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[8] + P[9][15]*SPP[22] + P[12][15]*SPP[18]) + (SF[16]*SF[23] - SF[17]*SPP[21])*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[8] + P[9][1]*SPP[22] + P[12][1]*SPP[18]);
  907. nextP[1][3] = P[1][3]*SPP[6] - P[0][3]*SPP[2] - P[2][3]*SPP[9] + P[10][3]*SPP[22] + P[13][3]*SPP[17] + SPP[1]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[9] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) + SPP[15]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[9] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) - SPP[21]*(P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[9] + P[10][15]*SPP[22] + P[13][15]*SPP[17]) + (SF[16]*SF[23] - SF[17]*SPP[21])*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[9] + P[10][1]*SPP[22] + P[13][1]*SPP[17]);
  908. nextP[2][3] = P[0][3]*SPP[14] - P[1][3]*SPP[3] + P[2][3]*SPP[13] + P[11][3]*SPP[22] + P[14][3]*SPP[16] + SPP[1]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) + SPP[15]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]) - SPP[21]*(P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16]) + (SF[16]*SF[23] - SF[17]*SPP[21])*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]);
  909. nextP[3][3] = P[3][3] + P[0][3]*SPP[1] + P[1][3]*SPP[19] + P[2][3]*SPP[15] - P[15][3]*SPP[21] + dvyNoise*sq(SQ[6] - 2*q0*q3) + dvzNoise*sq(SQ[5] + 2*q0*q2) + SPP[1]*(P[3][0] + P[0][0]*SPP[1] + P[1][0]*SPP[19] + P[2][0]*SPP[15] - P[15][0]*SPP[21]) + SPP[19]*(P[3][1] + P[0][1]*SPP[1] + P[1][1]*SPP[19] + P[2][1]*SPP[15] - P[15][1]*SPP[21]) + SPP[15]*(P[3][2] + P[0][2]*SPP[1] + P[1][2]*SPP[19] + P[2][2]*SPP[15] - P[15][2]*SPP[21]) - SPP[21]*(P[3][15] + P[0][15]*SPP[1] + P[2][15]*SPP[15] - P[15][15]*SPP[21] + P[1][15]*(SF[16]*SF[23] - SF[17]*SPP[21])) + dvxNoise*sq(SG[1] + SG[2] - SG[3] - SQ[7]);
  910. nextP[0][4] = P[0][4]*SPP[5] - P[1][4]*SPP[4] + P[2][4]*SPP[8] + P[9][4]*SPP[22] + P[12][4]*SPP[18] + SF[22]*(P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[8] + P[9][15]*SPP[22] + P[12][15]*SPP[18]) + SPP[12]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[8] + P[9][1]*SPP[22] + P[12][1]*SPP[18]) + SPP[20]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[8] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) + SPP[11]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18]);
  911. nextP[1][4] = P[1][4]*SPP[6] - P[0][4]*SPP[2] - P[2][4]*SPP[9] + P[10][4]*SPP[22] + P[13][4]*SPP[17] + SF[22]*(P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[9] + P[10][15]*SPP[22] + P[13][15]*SPP[17]) + SPP[12]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[9] + P[10][1]*SPP[22] + P[13][1]*SPP[17]) + SPP[20]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[9] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) + SPP[11]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[9] + P[10][2]*SPP[22] + P[13][2]*SPP[17]);
  912. nextP[2][4] = P[0][4]*SPP[14] - P[1][4]*SPP[3] + P[2][4]*SPP[13] + P[11][4]*SPP[22] + P[14][4]*SPP[16] + SF[22]*(P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16]) + SPP[12]*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]) + SPP[20]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) + SPP[11]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]);
  913. nextP[3][4] = P[3][4] + SQ[2] + P[0][4]*SPP[1] + P[1][4]*SPP[19] + P[2][4]*SPP[15] - P[15][4]*SPP[21] + SF[22]*(P[3][15] + P[0][15]*SPP[1] + P[1][15]*SPP[19] + P[2][15]*SPP[15] - P[15][15]*SPP[21]) + SPP[12]*(P[3][1] + P[0][1]*SPP[1] + P[1][1]*SPP[19] + P[2][1]*SPP[15] - P[15][1]*SPP[21]) + SPP[20]*(P[3][0] + P[0][0]*SPP[1] + P[1][0]*SPP[19] + P[2][0]*SPP[15] - P[15][0]*SPP[21]) + SPP[11]*(P[3][2] + P[0][2]*SPP[1] + P[1][2]*SPP[19] + P[2][2]*SPP[15] - P[15][2]*SPP[21]);
  914. nextP[4][4] = P[4][4] + P[15][4]*SF[22] + P[0][4]*SPP[20] + P[1][4]*SPP[12] + P[2][4]*SPP[11] + dvxNoise*sq(SQ[6] + 2*q0*q3) + dvzNoise*sq(SQ[4] - 2*q0*q1) + SF[22]*(P[4][15] + P[15][15]*SF[22] + P[0][15]*SPP[20] + P[1][15]*SPP[12] + P[2][15]*SPP[11]) + SPP[12]*(P[4][1] + P[15][1]*SF[22] + P[0][1]*SPP[20] + P[1][1]*SPP[12] + P[2][1]*SPP[11]) + SPP[20]*(P[4][0] + P[15][0]*SF[22] + P[0][0]*SPP[20] + P[1][0]*SPP[12] + P[2][0]*SPP[11]) + SPP[11]*(P[4][2] + P[15][2]*SF[22] + P[0][2]*SPP[20] + P[1][2]*SPP[12] + P[2][2]*SPP[11]) + dvyNoise*sq(SG[1] - SG[2] + SG[3] - SQ[7]);
  915. nextP[0][5] = P[0][5]*SPP[5] - P[1][5]*SPP[4] + P[2][5]*SPP[8] + P[9][5]*SPP[22] + P[12][5]*SPP[18] + SF[20]*(P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[8] + P[9][15]*SPP[22] + P[12][15]*SPP[18]) - SPP[7]*(P[0][0]*SPP[5] - P[1][0]*SPP[4] + P[2][0]*SPP[8] + P[9][0]*SPP[22] + P[12][0]*SPP[18]) + SPP[0]*(P[0][2]*SPP[5] - P[1][2]*SPP[4] + P[2][2]*SPP[8] + P[9][2]*SPP[22] + P[12][2]*SPP[18]) + SPP[10]*(P[0][1]*SPP[5] - P[1][1]*SPP[4] + P[2][1]*SPP[8] + P[9][1]*SPP[22] + P[12][1]*SPP[18]);
  916. nextP[1][5] = P[1][5]*SPP[6] - P[0][5]*SPP[2] - P[2][5]*SPP[9] + P[10][5]*SPP[22] + P[13][5]*SPP[17] + SF[20]*(P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[9] + P[10][15]*SPP[22] + P[13][15]*SPP[17]) - SPP[7]*(P[1][0]*SPP[6] - P[0][0]*SPP[2] - P[2][0]*SPP[9] + P[10][0]*SPP[22] + P[13][0]*SPP[17]) + SPP[0]*(P[1][2]*SPP[6] - P[0][2]*SPP[2] - P[2][2]*SPP[9] + P[10][2]*SPP[22] + P[13][2]*SPP[17]) + SPP[10]*(P[1][1]*SPP[6] - P[0][1]*SPP[2] - P[2][1]*SPP[9] + P[10][1]*SPP[22] + P[13][1]*SPP[17]);
  917. nextP[2][5] = P[0][5]*SPP[14] - P[1][5]*SPP[3] + P[2][5]*SPP[13] + P[11][5]*SPP[22] + P[14][5]*SPP[16] + SF[20]*(P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16]) - SPP[7]*(P[0][0]*SPP[14] - P[1][0]*SPP[3] + P[2][0]*SPP[13] + P[11][0]*SPP[22] + P[14][0]*SPP[16]) + SPP[0]*(P[0][2]*SPP[14] - P[1][2]*SPP[3] + P[2][2]*SPP[13] + P[11][2]*SPP[22] + P[14][2]*SPP[16]) + SPP[10]*(P[0][1]*SPP[14] - P[1][1]*SPP[3] + P[2][1]*SPP[13] + P[11][1]*SPP[22] + P[14][1]*SPP[16]);
  918. nextP[3][5] = P[3][5] + SQ[1] + P[0][5]*SPP[1] + P[1][5]*SPP[19] + P[2][5]*SPP[15] - P[15][5]*SPP[21] + SF[20]*(P[3][15] + P[0][15]*SPP[1] + P[1][15]*SPP[19] + P[2][15]*SPP[15] - P[15][15]*SPP[21]) - SPP[7]*(P[3][0] + P[0][0]*SPP[1] + P[1][0]*SPP[19] + P[2][0]*SPP[15] - P[15][0]*SPP[21]) + SPP[0]*(P[3][2] + P[0][2]*SPP[1] + P[1][2]*SPP[19] + P[2][2]*SPP[15] - P[15][2]*SPP[21]) + SPP[10]*(P[3][1] + P[0][1]*SPP[1] + P[1][1]*SPP[19] + P[2][1]*SPP[15] - P[15][1]*SPP[21]);
  919. nextP[4][5] = P[4][5] + SQ[0] + P[15][5]*SF[22] + P[0][5]*SPP[20] + P[1][5]*SPP[12] + P[2][5]*SPP[11] + SF[20]*(P[4][15] + P[15][15]*SF[22] + P[0][15]*SPP[20] + P[1][15]*SPP[12] + P[2][15]*SPP[11]) - SPP[7]*(P[4][0] + P[15][0]*SF[22] + P[0][0]*SPP[20] + P[1][0]*SPP[12] + P[2][0]*SPP[11]) + SPP[0]*(P[4][2] + P[15][2]*SF[22] + P[0][2]*SPP[20] + P[1][2]*SPP[12] + P[2][2]*SPP[11]) + SPP[10]*(P[4][1] + P[15][1]*SF[22] + P[0][1]*SPP[20] + P[1][1]*SPP[12] + P[2][1]*SPP[11]);
  920. nextP[5][5] = P[5][5] + P[15][5]*SF[20] - P[0][5]*SPP[7] + P[1][5]*SPP[10] + P[2][5]*SPP[0] + dvxNoise*sq(SQ[5] - 2*q0*q2) + dvyNoise*sq(SQ[4] + 2*q0*q1) + SF[20]*(P[5][15] + P[15][15]*SF[20] - P[0][15]*SPP[7] + P[1][15]*SPP[10] + P[2][15]*SPP[0]) - SPP[7]*(P[5][0] + P[15][0]*SF[20] - P[0][0]*SPP[7] + P[1][0]*SPP[10] + P[2][0]*SPP[0]) + SPP[0]*(P[5][2] + P[15][2]*SF[20] - P[0][2]*SPP[7] + P[1][2]*SPP[10] + P[2][2]*SPP[0]) + SPP[10]*(P[5][1] + P[15][1]*SF[20] - P[0][1]*SPP[7] + P[1][1]*SPP[10] + P[2][1]*SPP[0]) + dvzNoise*sq(SG[1] - SG[2] - SG[3] + SQ[7]);
  921. nextP[0][6] = P[0][6]*SPP[5] - P[1][6]*SPP[4] + P[2][6]*SPP[8] + P[9][6]*SPP[22] + P[12][6]*SPP[18] + dt*(P[0][3]*SPP[5] - P[1][3]*SPP[4] + P[2][3]*SPP[8] + P[9][3]*SPP[22] + P[12][3]*SPP[18]);
  922. nextP[1][6] = P[1][6]*SPP[6] - P[0][6]*SPP[2] - P[2][6]*SPP[9] + P[10][6]*SPP[22] + P[13][6]*SPP[17] + dt*(P[1][3]*SPP[6] - P[0][3]*SPP[2] - P[2][3]*SPP[9] + P[10][3]*SPP[22] + P[13][3]*SPP[17]);
  923. nextP[2][6] = P[0][6]*SPP[14] - P[1][6]*SPP[3] + P[2][6]*SPP[13] + P[11][6]*SPP[22] + P[14][6]*SPP[16] + dt*(P[0][3]*SPP[14] - P[1][3]*SPP[3] + P[2][3]*SPP[13] + P[11][3]*SPP[22] + P[14][3]*SPP[16]);
  924. nextP[3][6] = P[3][6] + P[0][6]*SPP[1] + P[1][6]*SPP[19] + P[2][6]*SPP[15] - P[15][6]*SPP[21] + dt*(P[3][3] + P[0][3]*SPP[1] + P[1][3]*SPP[19] + P[2][3]*SPP[15] - P[15][3]*SPP[21]);
  925. nextP[4][6] = P[4][6] + P[15][6]*SF[22] + P[0][6]*SPP[20] + P[1][6]*SPP[12] + P[2][6]*SPP[11] + dt*(P[4][3] + P[15][3]*SF[22] + P[0][3]*SPP[20] + P[1][3]*SPP[12] + P[2][3]*SPP[11]);
  926. nextP[5][6] = P[5][6] + P[15][6]*SF[20] - P[0][6]*SPP[7] + P[1][6]*SPP[10] + P[2][6]*SPP[0] + dt*(P[5][3] + P[15][3]*SF[20] - P[0][3]*SPP[7] + P[1][3]*SPP[10] + P[2][3]*SPP[0]);
  927. nextP[6][6] = P[6][6] + P[3][6]*dt + dt*(P[6][3] + P[3][3]*dt);
  928. nextP[0][7] = P[0][7]*SPP[5] - P[1][7]*SPP[4] + P[2][7]*SPP[8] + P[9][7]*SPP[22] + P[12][7]*SPP[18] + dt*(P[0][4]*SPP[5] - P[1][4]*SPP[4] + P[2][4]*SPP[8] + P[9][4]*SPP[22] + P[12][4]*SPP[18]);
  929. nextP[1][7] = P[1][7]*SPP[6] - P[0][7]*SPP[2] - P[2][7]*SPP[9] + P[10][7]*SPP[22] + P[13][7]*SPP[17] + dt*(P[1][4]*SPP[6] - P[0][4]*SPP[2] - P[2][4]*SPP[9] + P[10][4]*SPP[22] + P[13][4]*SPP[17]);
  930. nextP[2][7] = P[0][7]*SPP[14] - P[1][7]*SPP[3] + P[2][7]*SPP[13] + P[11][7]*SPP[22] + P[14][7]*SPP[16] + dt*(P[0][4]*SPP[14] - P[1][4]*SPP[3] + P[2][4]*SPP[13] + P[11][4]*SPP[22] + P[14][4]*SPP[16]);
  931. nextP[3][7] = P[3][7] + P[0][7]*SPP[1] + P[1][7]*SPP[19] + P[2][7]*SPP[15] - P[15][7]*SPP[21] + dt*(P[3][4] + P[0][4]*SPP[1] + P[1][4]*SPP[19] + P[2][4]*SPP[15] - P[15][4]*SPP[21]);
  932. nextP[4][7] = P[4][7] + P[15][7]*SF[22] + P[0][7]*SPP[20] + P[1][7]*SPP[12] + P[2][7]*SPP[11] + dt*(P[4][4] + P[15][4]*SF[22] + P[0][4]*SPP[20] + P[1][4]*SPP[12] + P[2][4]*SPP[11]);
  933. nextP[5][7] = P[5][7] + P[15][7]*SF[20] - P[0][7]*SPP[7] + P[1][7]*SPP[10] + P[2][7]*SPP[0] + dt*(P[5][4] + P[15][4]*SF[20] - P[0][4]*SPP[7] + P[1][4]*SPP[10] + P[2][4]*SPP[0]);
  934. nextP[6][7] = P[6][7] + P[3][7]*dt + dt*(P[6][4] + P[3][4]*dt);
  935. nextP[7][7] = P[7][7] + P[4][7]*dt + dt*(P[7][4] + P[4][4]*dt);
  936. nextP[0][8] = P[0][8]*SPP[5] - P[1][8]*SPP[4] + P[2][8]*SPP[8] + P[9][8]*SPP[22] + P[12][8]*SPP[18] + dt*(P[0][5]*SPP[5] - P[1][5]*SPP[4] + P[2][5]*SPP[8] + P[9][5]*SPP[22] + P[12][5]*SPP[18]);
  937. nextP[1][8] = P[1][8]*SPP[6] - P[0][8]*SPP[2] - P[2][8]*SPP[9] + P[10][8]*SPP[22] + P[13][8]*SPP[17] + dt*(P[1][5]*SPP[6] - P[0][5]*SPP[2] - P[2][5]*SPP[9] + P[10][5]*SPP[22] + P[13][5]*SPP[17]);
  938. nextP[2][8] = P[0][8]*SPP[14] - P[1][8]*SPP[3] + P[2][8]*SPP[13] + P[11][8]*SPP[22] + P[14][8]*SPP[16] + dt*(P[0][5]*SPP[14] - P[1][5]*SPP[3] + P[2][5]*SPP[13] + P[11][5]*SPP[22] + P[14][5]*SPP[16]);
  939. nextP[3][8] = P[3][8] + P[0][8]*SPP[1] + P[1][8]*SPP[19] + P[2][8]*SPP[15] - P[15][8]*SPP[21] + dt*(P[3][5] + P[0][5]*SPP[1] + P[1][5]*SPP[19] + P[2][5]*SPP[15] - P[15][5]*SPP[21]);
  940. nextP[4][8] = P[4][8] + P[15][8]*SF[22] + P[0][8]*SPP[20] + P[1][8]*SPP[12] + P[2][8]*SPP[11] + dt*(P[4][5] + P[15][5]*SF[22] + P[0][5]*SPP[20] + P[1][5]*SPP[12] + P[2][5]*SPP[11]);
  941. nextP[5][8] = P[5][8] + P[15][8]*SF[20] - P[0][8]*SPP[7] + P[1][8]*SPP[10] + P[2][8]*SPP[0] + dt*(P[5][5] + P[15][5]*SF[20] - P[0][5]*SPP[7] + P[1][5]*SPP[10] + P[2][5]*SPP[0]);
  942. nextP[6][8] = P[6][8] + P[3][8]*dt + dt*(P[6][5] + P[3][5]*dt);
  943. nextP[7][8] = P[7][8] + P[4][8]*dt + dt*(P[7][5] + P[4][5]*dt);
  944. nextP[8][8] = P[8][8] + P[5][8]*dt + dt*(P[8][5] + P[5][5]*dt);
  945. nextP[0][9] = P[0][9]*SPP[5] - P[1][9]*SPP[4] + P[2][9]*SPP[8] + P[9][9]*SPP[22] + P[12][9]*SPP[18];
  946. nextP[1][9] = P[1][9]*SPP[6] - P[0][9]*SPP[2] - P[2][9]*SPP[9] + P[10][9]*SPP[22] + P[13][9]*SPP[17];
  947. nextP[2][9] = P[0][9]*SPP[14] - P[1][9]*SPP[3] + P[2][9]*SPP[13] + P[11][9]*SPP[22] + P[14][9]*SPP[16];
  948. nextP[3][9] = P[3][9] + P[0][9]*SPP[1] + P[1][9]*SPP[19] + P[2][9]*SPP[15] - P[15][9]*SPP[21];
  949. nextP[4][9] = P[4][9] + P[15][9]*SF[22] + P[0][9]*SPP[20] + P[1][9]*SPP[12] + P[2][9]*SPP[11];
  950. nextP[5][9] = P[5][9] + P[15][9]*SF[20] - P[0][9]*SPP[7] + P[1][9]*SPP[10] + P[2][9]*SPP[0];
  951. nextP[6][9] = P[6][9] + P[3][9]*dt;
  952. nextP[7][9] = P[7][9] + P[4][9]*dt;
  953. nextP[8][9] = P[8][9] + P[5][9]*dt;
  954. nextP[9][9] = P[9][9];
  955. nextP[0][10] = P[0][10]*SPP[5] - P[1][10]*SPP[4] + P[2][10]*SPP[8] + P[9][10]*SPP[22] + P[12][10]*SPP[18];
  956. nextP[1][10] = P[1][10]*SPP[6] - P[0][10]*SPP[2] - P[2][10]*SPP[9] + P[10][10]*SPP[22] + P[13][10]*SPP[17];
  957. nextP[2][10] = P[0][10]*SPP[14] - P[1][10]*SPP[3] + P[2][10]*SPP[13] + P[11][10]*SPP[22] + P[14][10]*SPP[16];
  958. nextP[3][10] = P[3][10] + P[0][10]*SPP[1] + P[1][10]*SPP[19] + P[2][10]*SPP[15] - P[15][10]*SPP[21];
  959. nextP[4][10] = P[4][10] + P[15][10]*SF[22] + P[0][10]*SPP[20] + P[1][10]*SPP[12] + P[2][10]*SPP[11];
  960. nextP[5][10] = P[5][10] + P[15][10]*SF[20] - P[0][10]*SPP[7] + P[1][10]*SPP[10] + P[2][10]*SPP[0];
  961. nextP[6][10] = P[6][10] + P[3][10]*dt;
  962. nextP[7][10] = P[7][10] + P[4][10]*dt;
  963. nextP[8][10] = P[8][10] + P[5][10]*dt;
  964. nextP[9][10] = P[9][10];
  965. nextP[10][10] = P[10][10];
  966. nextP[0][11] = P[0][11]*SPP[5] - P[1][11]*SPP[4] + P[2][11]*SPP[8] + P[9][11]*SPP[22] + P[12][11]*SPP[18];
  967. nextP[1][11] = P[1][11]*SPP[6] - P[0][11]*SPP[2] - P[2][11]*SPP[9] + P[10][11]*SPP[22] + P[13][11]*SPP[17];
  968. nextP[2][11] = P[0][11]*SPP[14] - P[1][11]*SPP[3] + P[2][11]*SPP[13] + P[11][11]*SPP[22] + P[14][11]*SPP[16];
  969. nextP[3][11] = P[3][11] + P[0][11]*SPP[1] + P[1][11]*SPP[19] + P[2][11]*SPP[15] - P[15][11]*SPP[21];
  970. nextP[4][11] = P[4][11] + P[15][11]*SF[22] + P[0][11]*SPP[20] + P[1][11]*SPP[12] + P[2][11]*SPP[11];
  971. nextP[5][11] = P[5][11] + P[15][11]*SF[20] - P[0][11]*SPP[7] + P[1][11]*SPP[10] + P[2][11]*SPP[0];
  972. nextP[6][11] = P[6][11] + P[3][11]*dt;
  973. nextP[7][11] = P[7][11] + P[4][11]*dt;
  974. nextP[8][11] = P[8][11] + P[5][11]*dt;
  975. nextP[9][11] = P[9][11];
  976. nextP[10][11] = P[10][11];
  977. nextP[11][11] = P[11][11];
  978. nextP[0][12] = P[0][12]*SPP[5] - P[1][12]*SPP[4] + P[2][12]*SPP[8] + P[9][12]*SPP[22] + P[12][12]*SPP[18];
  979. nextP[1][12] = P[1][12]*SPP[6] - P[0][12]*SPP[2] - P[2][12]*SPP[9] + P[10][12]*SPP[22] + P[13][12]*SPP[17];
  980. nextP[2][12] = P[0][12]*SPP[14] - P[1][12]*SPP[3] + P[2][12]*SPP[13] + P[11][12]*SPP[22] + P[14][12]*SPP[16];
  981. nextP[3][12] = P[3][12] + P[0][12]*SPP[1] + P[1][12]*SPP[19] + P[2][12]*SPP[15] - P[15][12]*SPP[21];
  982. nextP[4][12] = P[4][12] + P[15][12]*SF[22] + P[0][12]*SPP[20] + P[1][12]*SPP[12] + P[2][12]*SPP[11];
  983. nextP[5][12] = P[5][12] + P[15][12]*SF[20] - P[0][12]*SPP[7] + P[1][12]*SPP[10] + P[2][12]*SPP[0];
  984. nextP[6][12] = P[6][12] + P[3][12]*dt;
  985. nextP[7][12] = P[7][12] + P[4][12]*dt;
  986. nextP[8][12] = P[8][12] + P[5][12]*dt;
  987. nextP[9][12] = P[9][12];
  988. nextP[10][12] = P[10][12];
  989. nextP[11][12] = P[11][12];
  990. nextP[12][12] = P[12][12];
  991. nextP[0][13] = P[0][13]*SPP[5] - P[1][13]*SPP[4] + P[2][13]*SPP[8] + P[9][13]*SPP[22] + P[12][13]*SPP[18];
  992. nextP[1][13] = P[1][13]*SPP[6] - P[0][13]*SPP[2] - P[2][13]*SPP[9] + P[10][13]*SPP[22] + P[13][13]*SPP[17];
  993. nextP[2][13] = P[0][13]*SPP[14] - P[1][13]*SPP[3] + P[2][13]*SPP[13] + P[11][13]*SPP[22] + P[14][13]*SPP[16];
  994. nextP[3][13] = P[3][13] + P[0][13]*SPP[1] + P[1][13]*SPP[19] + P[2][13]*SPP[15] - P[15][13]*SPP[21];
  995. nextP[4][13] = P[4][13] + P[15][13]*SF[22] + P[0][13]*SPP[20] + P[1][13]*SPP[12] + P[2][13]*SPP[11];
  996. nextP[5][13] = P[5][13] + P[15][13]*SF[20] - P[0][13]*SPP[7] + P[1][13]*SPP[10] + P[2][13]*SPP[0];
  997. nextP[6][13] = P[6][13] + P[3][13]*dt;
  998. nextP[7][13] = P[7][13] + P[4][13]*dt;
  999. nextP[8][13] = P[8][13] + P[5][13]*dt;
  1000. nextP[9][13] = P[9][13];
  1001. nextP[10][13] = P[10][13];
  1002. nextP[11][13] = P[11][13];
  1003. nextP[12][13] = P[12][13];
  1004. nextP[13][13] = P[13][13];
  1005. nextP[0][14] = P[0][14]*SPP[5] - P[1][14]*SPP[4] + P[2][14]*SPP[8] + P[9][14]*SPP[22] + P[12][14]*SPP[18];
  1006. nextP[1][14] = P[1][14]*SPP[6] - P[0][14]*SPP[2] - P[2][14]*SPP[9] + P[10][14]*SPP[22] + P[13][14]*SPP[17];
  1007. nextP[2][14] = P[0][14]*SPP[14] - P[1][14]*SPP[3] + P[2][14]*SPP[13] + P[11][14]*SPP[22] + P[14][14]*SPP[16];
  1008. nextP[3][14] = P[3][14] + P[0][14]*SPP[1] + P[1][14]*SPP[19] + P[2][14]*SPP[15] - P[15][14]*SPP[21];
  1009. nextP[4][14] = P[4][14] + P[15][14]*SF[22] + P[0][14]*SPP[20] + P[1][14]*SPP[12] + P[2][14]*SPP[11];
  1010. nextP[5][14] = P[5][14] + P[15][14]*SF[20] - P[0][14]*SPP[7] + P[1][14]*SPP[10] + P[2][14]*SPP[0];
  1011. nextP[6][14] = P[6][14] + P[3][14]*dt;
  1012. nextP[7][14] = P[7][14] + P[4][14]*dt;
  1013. nextP[8][14] = P[8][14] + P[5][14]*dt;
  1014. nextP[9][14] = P[9][14];
  1015. nextP[10][14] = P[10][14];
  1016. nextP[11][14] = P[11][14];
  1017. nextP[12][14] = P[12][14];
  1018. nextP[13][14] = P[13][14];
  1019. nextP[14][14] = P[14][14];
  1020. nextP[0][15] = P[0][15]*SPP[5] - P[1][15]*SPP[4] + P[2][15]*SPP[8] + P[9][15]*SPP[22] + P[12][15]*SPP[18];
  1021. nextP[1][15] = P[1][15]*SPP[6] - P[0][15]*SPP[2] - P[2][15]*SPP[9] + P[10][15]*SPP[22] + P[13][15]*SPP[17];
  1022. nextP[2][15] = P[0][15]*SPP[14] - P[1][15]*SPP[3] + P[2][15]*SPP[13] + P[11][15]*SPP[22] + P[14][15]*SPP[16];
  1023. nextP[3][15] = P[3][15] + P[0][15]*SPP[1] + P[1][15]*SPP[19] + P[2][15]*SPP[15] - P[15][15]*SPP[21];
  1024. nextP[4][15] = P[4][15] + P[15][15]*SF[22] + P[0][15]*SPP[20] + P[1][15]*SPP[12] + P[2][15]*SPP[11];
  1025. nextP[5][15] = P[5][15] + P[15][15]*SF[20] - P[0][15]*SPP[7] + P[1][15]*SPP[10] + P[2][15]*SPP[0];
  1026. nextP[6][15] = P[6][15] + P[3][15]*dt;
  1027. nextP[7][15] = P[7][15] + P[4][15]*dt;
  1028. nextP[8][15] = P[8][15] + P[5][15]*dt;
  1029. nextP[9][15] = P[9][15];
  1030. nextP[10][15] = P[10][15];
  1031. nextP[11][15] = P[11][15];
  1032. nextP[12][15] = P[12][15];
  1033. nextP[13][15] = P[13][15];
  1034. nextP[14][15] = P[14][15];
  1035. nextP[15][15] = P[15][15];
  1036. if (stateIndexLim > 15) {
  1037. nextP[0][16] = P[0][16]*SPP[5] - P[1][16]*SPP[4] + P[2][16]*SPP[8] + P[9][16]*SPP[22] + P[12][16]*SPP[18];
  1038. nextP[1][16] = P[1][16]*SPP[6] - P[0][16]*SPP[2] - P[2][16]*SPP[9] + P[10][16]*SPP[22] + P[13][16]*SPP[17];
  1039. nextP[2][16] = P[0][16]*SPP[14] - P[1][16]*SPP[3] + P[2][16]*SPP[13] + P[11][16]*SPP[22] + P[14][16]*SPP[16];
  1040. nextP[3][16] = P[3][16] + P[0][16]*SPP[1] + P[1][16]*SPP[19] + P[2][16]*SPP[15] - P[15][16]*SPP[21];
  1041. nextP[4][16] = P[4][16] + P[15][16]*SF[22] + P[0][16]*SPP[20] + P[1][16]*SPP[12] + P[2][16]*SPP[11];
  1042. nextP[5][16] = P[5][16] + P[15][16]*SF[20] - P[0][16]*SPP[7] + P[1][16]*SPP[10] + P[2][16]*SPP[0];
  1043. nextP[6][16] = P[6][16] + P[3][16]*dt;
  1044. nextP[7][16] = P[7][16] + P[4][16]*dt;
  1045. nextP[8][16] = P[8][16] + P[5][16]*dt;
  1046. nextP[9][16] = P[9][16];
  1047. nextP[10][16] = P[10][16];
  1048. nextP[11][16] = P[11][16];
  1049. nextP[12][16] = P[12][16];
  1050. nextP[13][16] = P[13][16];
  1051. nextP[14][16] = P[14][16];
  1052. nextP[15][16] = P[15][16];
  1053. nextP[16][16] = P[16][16];
  1054. nextP[0][17] = P[0][17]*SPP[5] - P[1][17]*SPP[4] + P[2][17]*SPP[8] + P[9][17]*SPP[22] + P[12][17]*SPP[18];
  1055. nextP[1][17] = P[1][17]*SPP[6] - P[0][17]*SPP[2] - P[2][17]*SPP[9] + P[10][17]*SPP[22] + P[13][17]*SPP[17];
  1056. nextP[2][17] = P[0][17]*SPP[14] - P[1][17]*SPP[3] + P[2][17]*SPP[13] + P[11][17]*SPP[22] + P[14][17]*SPP[16];
  1057. nextP[3][17] = P[3][17] + P[0][17]*SPP[1] + P[1][17]*SPP[19] + P[2][17]*SPP[15] - P[15][17]*SPP[21];
  1058. nextP[4][17] = P[4][17] + P[15][17]*SF[22] + P[0][17]*SPP[20] + P[1][17]*SPP[12] + P[2][17]*SPP[11];
  1059. nextP[5][17] = P[5][17] + P[15][17]*SF[20] - P[0][17]*SPP[7] + P[1][17]*SPP[10] + P[2][17]*SPP[0];
  1060. nextP[6][17] = P[6][17] + P[3][17]*dt;
  1061. nextP[7][17] = P[7][17] + P[4][17]*dt;
  1062. nextP[8][17] = P[8][17] + P[5][17]*dt;
  1063. nextP[9][17] = P[9][17];
  1064. nextP[10][17] = P[10][17];
  1065. nextP[11][17] = P[11][17];
  1066. nextP[12][17] = P[12][17];
  1067. nextP[13][17] = P[13][17];
  1068. nextP[14][17] = P[14][17];
  1069. nextP[15][17] = P[15][17];
  1070. nextP[16][17] = P[16][17];
  1071. nextP[17][17] = P[17][17];
  1072. nextP[0][18] = P[0][18]*SPP[5] - P[1][18]*SPP[4] + P[2][18]*SPP[8] + P[9][18]*SPP[22] + P[12][18]*SPP[18];
  1073. nextP[1][18] = P[1][18]*SPP[6] - P[0][18]*SPP[2] - P[2][18]*SPP[9] + P[10][18]*SPP[22] + P[13][18]*SPP[17];
  1074. nextP[2][18] = P[0][18]*SPP[14] - P[1][18]*SPP[3] + P[2][18]*SPP[13] + P[11][18]*SPP[22] + P[14][18]*SPP[16];
  1075. nextP[3][18] = P[3][18] + P[0][18]*SPP[1] + P[1][18]*SPP[19] + P[2][18]*SPP[15] - P[15][18]*SPP[21];
  1076. nextP[4][18] = P[4][18] + P[15][18]*SF[22] + P[0][18]*SPP[20] + P[1][18]*SPP[12] + P[2][18]*SPP[11];
  1077. nextP[5][18] = P[5][18] + P[15][18]*SF[20] - P[0][18]*SPP[7] + P[1][18]*SPP[10] + P[2][18]*SPP[0];
  1078. nextP[6][18] = P[6][18] + P[3][18]*dt;
  1079. nextP[7][18] = P[7][18] + P[4][18]*dt;
  1080. nextP[8][18] = P[8][18] + P[5][18]*dt;
  1081. nextP[9][18] = P[9][18];
  1082. nextP[10][18] = P[10][18];
  1083. nextP[11][18] = P[11][18];
  1084. nextP[12][18] = P[12][18];
  1085. nextP[13][18] = P[13][18];
  1086. nextP[14][18] = P[14][18];
  1087. nextP[15][18] = P[15][18];
  1088. nextP[16][18] = P[16][18];
  1089. nextP[17][18] = P[17][18];
  1090. nextP[18][18] = P[18][18];
  1091. nextP[0][19] = P[0][19]*SPP[5] - P[1][19]*SPP[4] + P[2][19]*SPP[8] + P[9][19]*SPP[22] + P[12][19]*SPP[18];
  1092. nextP[1][19] = P[1][19]*SPP[6] - P[0][19]*SPP[2] - P[2][19]*SPP[9] + P[10][19]*SPP[22] + P[13][19]*SPP[17];
  1093. nextP[2][19] = P[0][19]*SPP[14] - P[1][19]*SPP[3] + P[2][19]*SPP[13] + P[11][19]*SPP[22] + P[14][19]*SPP[16];
  1094. nextP[3][19] = P[3][19] + P[0][19]*SPP[1] + P[1][19]*SPP[19] + P[2][19]*SPP[15] - P[15][19]*SPP[21];
  1095. nextP[4][19] = P[4][19] + P[15][19]*SF[22] + P[0][19]*SPP[20] + P[1][19]*SPP[12] + P[2][19]*SPP[11];
  1096. nextP[5][19] = P[5][19] + P[15][19]*SF[20] - P[0][19]*SPP[7] + P[1][19]*SPP[10] + P[2][19]*SPP[0];
  1097. nextP[6][19] = P[6][19] + P[3][19]*dt;
  1098. nextP[7][19] = P[7][19] + P[4][19]*dt;
  1099. nextP[8][19] = P[8][19] + P[5][19]*dt;
  1100. nextP[9][19] = P[9][19];
  1101. nextP[10][19] = P[10][19];
  1102. nextP[11][19] = P[11][19];
  1103. nextP[12][19] = P[12][19];
  1104. nextP[13][19] = P[13][19];
  1105. nextP[14][19] = P[14][19];
  1106. nextP[15][19] = P[15][19];
  1107. nextP[16][19] = P[16][19];
  1108. nextP[17][19] = P[17][19];
  1109. nextP[18][19] = P[18][19];
  1110. nextP[19][19] = P[19][19];
  1111. nextP[0][20] = P[0][20]*SPP[5] - P[1][20]*SPP[4] + P[2][20]*SPP[8] + P[9][20]*SPP[22] + P[12][20]*SPP[18];
  1112. nextP[1][20] = P[1][20]*SPP[6] - P[0][20]*SPP[2] - P[2][20]*SPP[9] + P[10][20]*SPP[22] + P[13][20]*SPP[17];
  1113. nextP[2][20] = P[0][20]*SPP[14] - P[1][20]*SPP[3] + P[2][20]*SPP[13] + P[11][20]*SPP[22] + P[14][20]*SPP[16];
  1114. nextP[3][20] = P[3][20] + P[0][20]*SPP[1] + P[1][20]*SPP[19] + P[2][20]*SPP[15] - P[15][20]*SPP[21];
  1115. nextP[4][20] = P[4][20] + P[15][20]*SF[22] + P[0][20]*SPP[20] + P[1][20]*SPP[12] + P[2][20]*SPP[11];
  1116. nextP[5][20] = P[5][20] + P[15][20]*SF[20] - P[0][20]*SPP[7] + P[1][20]*SPP[10] + P[2][20]*SPP[0];
  1117. nextP[6][20] = P[6][20] + P[3][20]*dt;
  1118. nextP[7][20] = P[7][20] + P[4][20]*dt;
  1119. nextP[8][20] = P[8][20] + P[5][20]*dt;
  1120. nextP[9][20] = P[9][20];
  1121. nextP[10][20] = P[10][20];
  1122. nextP[11][20] = P[11][20];
  1123. nextP[12][20] = P[12][20];
  1124. nextP[13][20] = P[13][20];
  1125. nextP[14][20] = P[14][20];
  1126. nextP[15][20] = P[15][20];
  1127. nextP[16][20] = P[16][20];
  1128. nextP[17][20] = P[17][20];
  1129. nextP[18][20] = P[18][20];
  1130. nextP[19][20] = P[19][20];
  1131. nextP[20][20] = P[20][20];
  1132. nextP[0][21] = P[0][21]*SPP[5] - P[1][21]*SPP[4] + P[2][21]*SPP[8] + P[9][21]*SPP[22] + P[12][21]*SPP[18];
  1133. nextP[1][21] = P[1][21]*SPP[6] - P[0][21]*SPP[2] - P[2][21]*SPP[9] + P[10][21]*SPP[22] + P[13][21]*SPP[17];
  1134. nextP[2][21] = P[0][21]*SPP[14] - P[1][21]*SPP[3] + P[2][21]*SPP[13] + P[11][21]*SPP[22] + P[14][21]*SPP[16];
  1135. nextP[3][21] = P[3][21] + P[0][21]*SPP[1] + P[1][21]*SPP[19] + P[2][21]*SPP[15] - P[15][21]*SPP[21];
  1136. nextP[4][21] = P[4][21] + P[15][21]*SF[22] + P[0][21]*SPP[20] + P[1][21]*SPP[12] + P[2][21]*SPP[11];
  1137. nextP[5][21] = P[5][21] + P[15][21]*SF[20] - P[0][21]*SPP[7] + P[1][21]*SPP[10] + P[2][21]*SPP[0];
  1138. nextP[6][21] = P[6][21] + P[3][21]*dt;
  1139. nextP[7][21] = P[7][21] + P[4][21]*dt;
  1140. nextP[8][21] = P[8][21] + P[5][21]*dt;
  1141. nextP[9][21] = P[9][21];
  1142. nextP[10][21] = P[10][21];
  1143. nextP[11][21] = P[11][21];
  1144. nextP[12][21] = P[12][21];
  1145. nextP[13][21] = P[13][21];
  1146. nextP[14][21] = P[14][21];
  1147. nextP[15][21] = P[15][21];
  1148. nextP[16][21] = P[16][21];
  1149. nextP[17][21] = P[17][21];
  1150. nextP[18][21] = P[18][21];
  1151. nextP[19][21] = P[19][21];
  1152. nextP[20][21] = P[20][21];
  1153. nextP[21][21] = P[21][21];
  1154. if (stateIndexLim > 21) {
  1155. nextP[0][22] = P[0][22]*SPP[5] - P[1][22]*SPP[4] + P[2][22]*SPP[8] + P[9][22]*SPP[22] + P[12][22]*SPP[18];
  1156. nextP[1][22] = P[1][22]*SPP[6] - P[0][22]*SPP[2] - P[2][22]*SPP[9] + P[10][22]*SPP[22] + P[13][22]*SPP[17];
  1157. nextP[2][22] = P[0][22]*SPP[14] - P[1][22]*SPP[3] + P[2][22]*SPP[13] + P[11][22]*SPP[22] + P[14][22]*SPP[16];
  1158. nextP[3][22] = P[3][22] + P[0][22]*SPP[1] + P[1][22]*SPP[19] + P[2][22]*SPP[15] - P[15][22]*SPP[21];
  1159. nextP[4][22] = P[4][22] + P[15][22]*SF[22] + P[0][22]*SPP[20] + P[1][22]*SPP[12] + P[2][22]*SPP[11];
  1160. nextP[5][22] = P[5][22] + P[15][22]*SF[20] - P[0][22]*SPP[7] + P[1][22]*SPP[10] + P[2][22]*SPP[0];
  1161. nextP[6][22] = P[6][22] + P[3][22]*dt;
  1162. nextP[7][22] = P[7][22] + P[4][22]*dt;
  1163. nextP[8][22] = P[8][22] + P[5][22]*dt;
  1164. nextP[9][22] = P[9][22];
  1165. nextP[10][22] = P[10][22];
  1166. nextP[11][22] = P[11][22];
  1167. nextP[12][22] = P[12][22];
  1168. nextP[13][22] = P[13][22];
  1169. nextP[14][22] = P[14][22];
  1170. nextP[15][22] = P[15][22];
  1171. nextP[16][22] = P[16][22];
  1172. nextP[17][22] = P[17][22];
  1173. nextP[18][22] = P[18][22];
  1174. nextP[19][22] = P[19][22];
  1175. nextP[20][22] = P[20][22];
  1176. nextP[21][22] = P[21][22];
  1177. nextP[22][22] = P[22][22];
  1178. nextP[0][23] = P[0][23]*SPP[5] - P[1][23]*SPP[4] + P[2][23]*SPP[8] + P[9][23]*SPP[22] + P[12][23]*SPP[18];
  1179. nextP[1][23] = P[1][23]*SPP[6] - P[0][23]*SPP[2] - P[2][23]*SPP[9] + P[10][23]*SPP[22] + P[13][23]*SPP[17];
  1180. nextP[2][23] = P[0][23]*SPP[14] - P[1][23]*SPP[3] + P[2][23]*SPP[13] + P[11][23]*SPP[22] + P[14][23]*SPP[16];
  1181. nextP[3][23] = P[3][23] + P[0][23]*SPP[1] + P[1][23]*SPP[19] + P[2][23]*SPP[15] - P[15][23]*SPP[21];
  1182. nextP[4][23] = P[4][23] + P[15][23]*SF[22] + P[0][23]*SPP[20] + P[1][23]*SPP[12] + P[2][23]*SPP[11];
  1183. nextP[5][23] = P[5][23] + P[15][23]*SF[20] - P[0][23]*SPP[7] + P[1][23]*SPP[10] + P[2][23]*SPP[0];
  1184. nextP[6][23] = P[6][23] + P[3][23]*dt;
  1185. nextP[7][23] = P[7][23] + P[4][23]*dt;
  1186. nextP[8][23] = P[8][23] + P[5][23]*dt;
  1187. nextP[9][23] = P[9][23];
  1188. nextP[10][23] = P[10][23];
  1189. nextP[11][23] = P[11][23];
  1190. nextP[12][23] = P[12][23];
  1191. nextP[13][23] = P[13][23];
  1192. nextP[14][23] = P[14][23];
  1193. nextP[15][23] = P[15][23];
  1194. nextP[16][23] = P[16][23];
  1195. nextP[17][23] = P[17][23];
  1196. nextP[18][23] = P[18][23];
  1197. nextP[19][23] = P[19][23];
  1198. nextP[20][23] = P[20][23];
  1199. nextP[21][23] = P[21][23];
  1200. nextP[22][23] = P[22][23];
  1201. nextP[23][23] = P[23][23];
  1202. }
  1203. }
  1204. // Copy upper diagonal to lower diagonal taking advantage of symmetry
  1205. for (uint8_t colIndex=0; colIndex<=stateIndexLim; colIndex++)
  1206. {
  1207. for (uint8_t rowIndex=0; rowIndex<colIndex; rowIndex++)
  1208. {
  1209. nextP[colIndex][rowIndex] = nextP[rowIndex][colIndex];
  1210. }
  1211. }
  1212. // add the general state process noise variances
  1213. for (uint8_t i=0; i<=stateIndexLim; i++)
  1214. {
  1215. nextP[i][i] = nextP[i][i] + processNoise[i];
  1216. }
  1217. // if the total position variance exceeds 1e4 (100m), then stop covariance
  1218. // growth by setting the predicted to the previous values
  1219. // This prevent an ill conditioned matrix from occurring for long periods
  1220. // without GPS
  1221. if ((P[6][6] + P[7][7]) > 1e4f)
  1222. {
  1223. for (uint8_t i=6; i<=7; i++)
  1224. {
  1225. for (uint8_t j=0; j<=stateIndexLim; j++)
  1226. {
  1227. nextP[i][j] = P[i][j];
  1228. nextP[j][i] = P[j][i];
  1229. }
  1230. }
  1231. }
  1232. // copy covariances to output
  1233. CopyCovariances();
  1234. // constrain diagonals to prevent ill-conditioning
  1235. ConstrainVariances();
  1236. hal.util->perf_end(_perf_CovariancePrediction);
  1237. }
  1238. // zero specified range of rows in the state covariance matrix
  1239. void NavEKF2_core::zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last)
  1240. {
  1241. uint8_t row;
  1242. for (row=first; row<=last; row++)
  1243. {
  1244. memset(&covMat[row][0], 0, sizeof(covMat[0][0])*24);
  1245. }
  1246. }
  1247. // zero specified range of columns in the state covariance matrix
  1248. void NavEKF2_core::zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last)
  1249. {
  1250. uint8_t row;
  1251. for (row=0; row<=23; row++)
  1252. {
  1253. memset(&covMat[row][first], 0, sizeof(covMat[0][0])*(1+last-first));
  1254. }
  1255. }
  1256. // reset the output data to the current EKF state
  1257. void NavEKF2_core::StoreOutputReset()
  1258. {
  1259. outputDataNew.quat = stateStruct.quat;
  1260. outputDataNew.velocity = stateStruct.velocity;
  1261. outputDataNew.position = stateStruct.position;
  1262. // write current measurement to entire table
  1263. for (uint8_t i=0; i<imu_buffer_length; i++) {
  1264. storedOutput[i] = outputDataNew;
  1265. }
  1266. outputDataDelayed = outputDataNew;
  1267. // reset the states for the complementary filter used to provide a vertical position dervative output
  1268. posDown = stateStruct.position.z;
  1269. posDownDerivative = stateStruct.velocity.z;
  1270. }
  1271. // Reset the stored output quaternion history to current EKF state
  1272. void NavEKF2_core::StoreQuatReset()
  1273. {
  1274. outputDataNew.quat = stateStruct.quat;
  1275. // write current measurement to entire table
  1276. for (uint8_t i=0; i<imu_buffer_length; i++) {
  1277. storedOutput[i].quat = outputDataNew.quat;
  1278. }
  1279. outputDataDelayed.quat = outputDataNew.quat;
  1280. }
  1281. // Rotate the stored output quaternion history through a quaternion rotation
  1282. void NavEKF2_core::StoreQuatRotate(const Quaternion &deltaQuat)
  1283. {
  1284. outputDataNew.quat = outputDataNew.quat*deltaQuat;
  1285. // write current measurement to entire table
  1286. for (uint8_t i=0; i<imu_buffer_length; i++) {
  1287. storedOutput[i].quat = storedOutput[i].quat*deltaQuat;
  1288. }
  1289. outputDataDelayed.quat = outputDataDelayed.quat*deltaQuat;
  1290. }
  1291. // calculate nav to body quaternions from body to nav rotation matrix
  1292. void NavEKF2_core::quat2Tbn(Matrix3f &Tbn, const Quaternion &quat) const
  1293. {
  1294. // Calculate the body to nav cosine matrix
  1295. quat.rotation_matrix(Tbn);
  1296. }
  1297. // force symmetry on the covariance matrix to prevent ill-conditioning
  1298. void NavEKF2_core::ForceSymmetry()
  1299. {
  1300. for (uint8_t i=1; i<=stateIndexLim; i++)
  1301. {
  1302. for (uint8_t j=0; j<=i-1; j++)
  1303. {
  1304. float temp = 0.5f*(P[i][j] + P[j][i]);
  1305. P[i][j] = temp;
  1306. P[j][i] = temp;
  1307. }
  1308. }
  1309. }
  1310. // copy covariances across from covariance prediction calculation
  1311. void NavEKF2_core::CopyCovariances()
  1312. {
  1313. // copy predicted covariances
  1314. for (uint8_t i=0; i<=stateIndexLim; i++) {
  1315. for (uint8_t j=0; j<=stateIndexLim; j++)
  1316. {
  1317. P[i][j] = nextP[i][j];
  1318. }
  1319. }
  1320. }
  1321. // constrain variances (diagonal terms) in the state covariance matrix to prevent ill-conditioning
  1322. void NavEKF2_core::ConstrainVariances()
  1323. {
  1324. for (uint8_t i=0; i<=2; i++) P[i][i] = constrain_float(P[i][i],0.0f,1.0f); // attitude error
  1325. for (uint8_t i=3; i<=5; i++) P[i][i] = constrain_float(P[i][i],0.0f,1.0e3f); // velocities
  1326. for (uint8_t i=6; i<=7; i++) P[i][i] = constrain_float(P[i][i],0.0f,1.0e6f);
  1327. P[8][8] = constrain_float(P[8][8],0.0f,1.0e6f); // vertical position
  1328. for (uint8_t i=9; i<=11; i++) P[i][i] = constrain_float(P[i][i],0.0f,sq(0.175f * dtEkfAvg)); // delta angle biases
  1329. if (PV_AidingMode != AID_NONE) {
  1330. for (uint8_t i=12; i<=14; i++) P[i][i] = constrain_float(P[i][i],0.0f,0.01f); // delta angle scale factors
  1331. } else {
  1332. // we can't reliably estimate scale factors when there is no aiding data due to transient manoeuvre induced innovations
  1333. // so inhibit estimation by keeping covariance elements at zero
  1334. zeroRows(P,12,14);
  1335. zeroCols(P,12,14);
  1336. }
  1337. P[15][15] = constrain_float(P[15][15],0.0f,sq(10.0f * dtEkfAvg)); // delta velocity bias
  1338. for (uint8_t i=16; i<=18; i++) P[i][i] = constrain_float(P[i][i],0.0f,0.01f); // earth magnetic field
  1339. for (uint8_t i=19; i<=21; i++) P[i][i] = constrain_float(P[i][i],0.0f,0.01f); // body magnetic field
  1340. for (uint8_t i=22; i<=23; i++) P[i][i] = constrain_float(P[i][i],0.0f,1.0e3f); // wind velocity
  1341. }
  1342. // constrain states using WMM tables and specified limit
  1343. void NavEKF2_core::MagTableConstrain(void)
  1344. {
  1345. // constrain to error from table earth field
  1346. float limit_ga = frontend->_mag_ef_limit * 0.001f;
  1347. stateStruct.earth_magfield.x = constrain_float(stateStruct.earth_magfield.x,
  1348. table_earth_field_ga.x-limit_ga,
  1349. table_earth_field_ga.x+limit_ga);
  1350. stateStruct.earth_magfield.y = constrain_float(stateStruct.earth_magfield.y,
  1351. table_earth_field_ga.y-limit_ga,
  1352. table_earth_field_ga.y+limit_ga);
  1353. stateStruct.earth_magfield.z = constrain_float(stateStruct.earth_magfield.z,
  1354. table_earth_field_ga.z-limit_ga,
  1355. table_earth_field_ga.z+limit_ga);
  1356. }
  1357. // constrain states to prevent ill-conditioning
  1358. void NavEKF2_core::ConstrainStates()
  1359. {
  1360. // attitude errors are limited between +-1
  1361. for (uint8_t i=0; i<=2; i++) statesArray[i] = constrain_float(statesArray[i],-1.0f,1.0f);
  1362. // velocity limit 500 m/sec (could set this based on some multiple of max airspeed * EAS2TAS)
  1363. for (uint8_t i=3; i<=5; i++) statesArray[i] = constrain_float(statesArray[i],-5.0e2f,5.0e2f);
  1364. // position limit 1000 km - TODO apply circular limit
  1365. for (uint8_t i=6; i<=7; i++) statesArray[i] = constrain_float(statesArray[i],-1.0e6f,1.0e6f);
  1366. // height limit covers home alt on everest through to home alt at SL and ballon drop
  1367. stateStruct.position.z = constrain_float(stateStruct.position.z,-4.0e4f,1.0e4f);
  1368. // gyro bias limit (this needs to be set based on manufacturers specs)
  1369. for (uint8_t i=9; i<=11; i++) statesArray[i] = constrain_float(statesArray[i],-GYRO_BIAS_LIMIT*dtEkfAvg,GYRO_BIAS_LIMIT*dtEkfAvg);
  1370. // gyro scale factor limit of +-5% (this needs to be set based on manufacturers specs)
  1371. for (uint8_t i=12; i<=14; i++) statesArray[i] = constrain_float(statesArray[i],0.95f,1.05f);
  1372. // Z accel bias limit 1.0 m/s^2 (this needs to be finalised from test data)
  1373. stateStruct.accel_zbias = constrain_float(stateStruct.accel_zbias,-1.0f*dtEkfAvg,1.0f*dtEkfAvg);
  1374. // earth magnetic field limit
  1375. if (frontend->_mag_ef_limit <= 0 || !have_table_earth_field) {
  1376. // constrain to +/-1Ga
  1377. for (uint8_t i=16; i<=18; i++) statesArray[i] = constrain_float(statesArray[i],-1.0f,1.0f);
  1378. } else {
  1379. // use table constrain
  1380. MagTableConstrain();
  1381. }
  1382. // body magnetic field limit
  1383. for (uint8_t i=19; i<=21; i++) statesArray[i] = constrain_float(statesArray[i],-0.5f,0.5f);
  1384. // wind velocity limit 100 m/s (could be based on some multiple of max airspeed * EAS2TAS) - TODO apply circular limit
  1385. for (uint8_t i=22; i<=23; i++) statesArray[i] = constrain_float(statesArray[i],-100.0f,100.0f);
  1386. // constrain the terrain state to be below the vehicle height unless we are using terrain as the height datum
  1387. if (!inhibitGndState) {
  1388. terrainState = MAX(terrainState, stateStruct.position.z + rngOnGnd);
  1389. }
  1390. }
  1391. // calculate the NED earth spin vector in rad/sec
  1392. void NavEKF2_core::calcEarthRateNED(Vector3f &omega, int32_t latitude) const
  1393. {
  1394. float lat_rad = radians(latitude*1.0e-7f);
  1395. omega.x = earthRate*cosf(lat_rad);
  1396. omega.y = 0;
  1397. omega.z = -earthRate*sinf(lat_rad);
  1398. }
  1399. // initialise the earth magnetic field states using declination, suppled roll/pitch
  1400. // and magnetometer measurements and return initial attitude quaternion
  1401. Quaternion NavEKF2_core::calcQuatAndFieldStates(float roll, float pitch)
  1402. {
  1403. // declare local variables required to calculate initial orientation and magnetic field
  1404. float yaw;
  1405. Matrix3f Tbn;
  1406. Vector3f initMagNED;
  1407. Quaternion initQuat;
  1408. if (use_compass()) {
  1409. // calculate rotation matrix from body to NED frame
  1410. Tbn.from_euler(roll, pitch, 0.0f);
  1411. // read the magnetometer data
  1412. readMagData();
  1413. // rotate the magnetic field into NED axes
  1414. initMagNED = Tbn * magDataDelayed.mag;
  1415. // calculate heading of mag field rel to body heading
  1416. float magHeading = atan2f(initMagNED.y, initMagNED.x);
  1417. // get the magnetic declination
  1418. float magDecAng = MagDeclination();
  1419. // calculate yaw angle rel to true north
  1420. yaw = magDecAng - magHeading;
  1421. // calculate initial filter quaternion states using yaw from magnetometer
  1422. // store the yaw change so that it can be retrieved externally for use by the control loops to prevent yaw disturbances following a reset
  1423. Vector3f tempEuler;
  1424. stateStruct.quat.to_euler(tempEuler.x, tempEuler.y, tempEuler.z);
  1425. // this check ensures we accumulate the resets that occur within a single iteration of the EKF
  1426. if (imuSampleTime_ms != lastYawReset_ms) {
  1427. yawResetAngle = 0.0f;
  1428. }
  1429. yawResetAngle += wrap_PI(yaw - tempEuler.z);
  1430. lastYawReset_ms = imuSampleTime_ms;
  1431. // calculate an initial quaternion using the new yaw value
  1432. initQuat.from_euler(roll, pitch, yaw);
  1433. // zero the attitude covariances because the corelations will now be invalid
  1434. zeroAttCovOnly();
  1435. // calculate initial Tbn matrix and rotate Mag measurements into NED
  1436. // to set initial NED magnetic field states
  1437. // don't do this if the earth field has already been learned
  1438. if (!magFieldLearned) {
  1439. initQuat.rotation_matrix(Tbn);
  1440. if (have_table_earth_field && frontend->_mag_ef_limit > 0) {
  1441. stateStruct.earth_magfield = table_earth_field_ga;
  1442. } else {
  1443. stateStruct.earth_magfield = Tbn * magDataDelayed.mag;
  1444. }
  1445. // set the NE earth magnetic field states using the published declination
  1446. // and set the corresponding variances and covariances
  1447. alignMagStateDeclination();
  1448. // set the remaining variances and covariances
  1449. zeroRows(P,18,21);
  1450. zeroCols(P,18,21);
  1451. P[18][18] = sq(frontend->_magNoise);
  1452. P[19][19] = P[18][18];
  1453. P[20][20] = P[18][18];
  1454. P[21][21] = P[18][18];
  1455. }
  1456. // record the fact we have initialised the magnetic field states
  1457. recordMagReset();
  1458. // clear mag state reset request
  1459. magStateResetRequest = false;
  1460. } else {
  1461. // this function should not be called if there is no compass data but if is is, return the
  1462. // current attitude
  1463. initQuat = stateStruct.quat;
  1464. }
  1465. // return attitude quaternion
  1466. return initQuat;
  1467. }
  1468. // zero the attitude covariances, but preserve the variances
  1469. void NavEKF2_core::zeroAttCovOnly()
  1470. {
  1471. float varTemp[3];
  1472. for (uint8_t index=0; index<=2; index++) {
  1473. varTemp[index] = P[index][index];
  1474. }
  1475. zeroCols(P,0,2);
  1476. zeroRows(P,0,2);
  1477. for (uint8_t index=0; index<=2; index++) {
  1478. P[index][index] = varTemp[index];
  1479. }
  1480. }