AP_NavEKF3_core.cpp 112 KB

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