calcP.cpp 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556
  1. float t2 = dax*0.5f;
  2. float t3 = dax_b*0.5f;
  3. float t4 = t2-t3;
  4. float t5 = day*0.5f;
  5. float t6 = day_b*0.5f;
  6. float t7 = t5-t6;
  7. float t8 = daz*0.5f;
  8. float t9 = daz_b*0.5f;
  9. float t10 = t8-t9;
  10. float t11 = q2*t4*0.5f;
  11. float t12 = q1*t7*0.5f;
  12. float t13 = q0*t10*0.5f;
  13. float t14 = q2*0.5f;
  14. float t15 = q3*t4*0.5f;
  15. float t16 = q1*t10*0.5f;
  16. float t17 = q1*0.5f;
  17. float t18 = q0*t4*0.5f;
  18. float t19 = q3*t7*0.5f;
  19. float t20 = q0*0.5f;
  20. float t21 = q2*t7*0.5f;
  21. float t22 = q3*t10*0.5f;
  22. float t23 = q0*t7*0.5f;
  23. float t24 = q3*0.5f;
  24. float t25 = q1*t4*0.5f;
  25. float t26 = q2*t10*0.5f;
  26. float t27 = t11+t12+t13-t24;
  27. float t28 = t14+t15+t16-t23;
  28. float t29 = q2*t28*2.0f;
  29. float t30 = t17+t18+t19-t26;
  30. float t31 = q1*t30*2.0f;
  31. float t32 = t20+t21+t22-t25;
  32. float t33 = q0*t32*2.0f;
  33. float t40 = q3*t27*2.0f;
  34. float t34 = t29+t31+t33-t40;
  35. float t35 = q0*q0;
  36. float t36 = q1*q1;
  37. float t37 = q2*q2;
  38. float t38 = q3*q3;
  39. float t39 = t35+t36+t37+t38;
  40. float t41 = t11+t12-t13+t24;
  41. float t42 = t14-t15+t16+t23;
  42. float t43 = q1*t42*2.0f;
  43. float t44 = -t17+t18+t19+t26;
  44. float t45 = q2*t44*2.0f;
  45. float t46 = t20-t21+t22+t25;
  46. float t47 = q3*t46*2.0f;
  47. float t57 = q0*t41*2.0f;
  48. float t48 = t43+t45+t47-t57;
  49. float t49 = -t14+t15+t16+t23;
  50. float t50 = q0*t49*2.0f;
  51. float t51 = t11-t12+t13+t24;
  52. float t52 = t20+t21-t22+t25;
  53. float t53 = q2*t52*2.0f;
  54. float t54 = t17-t18+t19+t26;
  55. float t55 = q3*t54*2.0f;
  56. float t58 = q1*t51*2.0f;
  57. float t56 = t50+t53+t55-t58;
  58. float t59 = OP[0][0]*t34;
  59. float t60 = OP[1][0]*t48;
  60. float t66 = OP[6][0]*t39;
  61. float t67 = OP[2][0]*t56;
  62. float t61 = t59+t60-t66-t67;
  63. float t62 = OP[0][1]*t34;
  64. float t63 = OP[1][1]*t48;
  65. float t64 = OP[0][2]*t34;
  66. float t65 = OP[1][2]*t48;
  67. float t72 = OP[6][1]*t39;
  68. float t73 = OP[2][1]*t56;
  69. float t68 = t62+t63-t72-t73;
  70. float t69 = t35+t36-t37-t38;
  71. float t86 = OP[6][2]*t39;
  72. float t87 = OP[2][2]*t56;
  73. float t70 = t64+t65-t86-t87;
  74. float t71 = dvx-dvx_b;
  75. float t74 = q0*q3*2.0f;
  76. float t81 = q1*q2*2.0f;
  77. float t75 = t74-t81;
  78. float t76 = q0*q2*2.0f;
  79. float t77 = q1*q3*2.0f;
  80. float t78 = t76+t77;
  81. float t79 = dvy-dvy_b;
  82. float t80 = dvz-dvz_b;
  83. float t82 = OP[0][10]*t34;
  84. float t83 = OP[1][10]*t48;
  85. float t103 = OP[6][10]*t39;
  86. float t104 = OP[2][10]*t56;
  87. float t84 = t82+t83-t103-t104;
  88. float t85 = t35-t36+t37-t38;
  89. float t88 = t74+t81;
  90. float t89 = OP[0][9]*t34;
  91. float t90 = OP[1][9]*t48;
  92. float t100 = OP[6][9]*t39;
  93. float t101 = OP[2][9]*t56;
  94. float t91 = t89+t90-t100-t101;
  95. float t92 = q0*q1*2.0f;
  96. float t96 = q2*q3*2.0f;
  97. float t93 = t92-t96;
  98. float t94 = OP[0][11]*t34;
  99. float t95 = OP[1][11]*t48;
  100. float t114 = OP[6][11]*t39;
  101. float t115 = OP[2][11]*t56;
  102. float t97 = t94+t95-t114-t115;
  103. float t98 = t35-t36-t37+t38;
  104. float t99 = t76-t77;
  105. float t102 = t92+t96;
  106. float t105 = OP[0][6]*t34;
  107. float t106 = OP[1][6]*t48;
  108. float t411 = OP[6][6]*t39;
  109. float t107 = t105+t106-t411-OP[2][6]*t56;
  110. float t108 = OP[0][7]*t34;
  111. float t109 = OP[1][7]*t48;
  112. float t412 = OP[6][7]*t39;
  113. float t110 = t108+t109-t412-OP[2][7]*t56;
  114. float t111 = OP[0][8]*t34;
  115. float t112 = OP[1][8]*t48;
  116. float t413 = OP[6][8]*t39;
  117. float t113 = t111+t112-t413-OP[2][8]*t56;
  118. float t116 = q0*t27*2.0f;
  119. float t117 = q1*t28*2.0f;
  120. float t118 = q3*t32*2.0f;
  121. float t128 = q2*t30*2.0f;
  122. float t119 = t116+t117+t118-t128;
  123. float t120 = q0*t46*2.0f;
  124. float t121 = q2*t42*2.0f;
  125. float t122 = q3*t41*2.0f;
  126. float t129 = q1*t44*2.0f;
  127. float t123 = t120+t121+t122-t129;
  128. float t124 = q1*t52*2.0f;
  129. float t125 = q2*t51*2.0f;
  130. float t126 = q3*t49*2.0f;
  131. float t130 = q0*t54*2.0f;
  132. float t127 = t124+t125+t126-t130;
  133. float t131 = OP[7][0]*t39;
  134. float t132 = OP[0][0]*t119;
  135. float t141 = OP[1][0]*t123;
  136. float t142 = OP[2][0]*t127;
  137. float t133 = t131+t132-t141-t142;
  138. float t134 = OP[7][1]*t39;
  139. float t135 = OP[0][1]*t119;
  140. float t147 = OP[1][1]*t123;
  141. float t148 = OP[2][1]*t127;
  142. float t136 = t134+t135-t147-t148;
  143. float t137 = OP[7][2]*t39;
  144. float t138 = OP[0][2]*t119;
  145. float t153 = OP[1][2]*t123;
  146. float t154 = OP[2][2]*t127;
  147. float t139 = t137+t138-t153-t154;
  148. float t140 = t39*t39;
  149. float t143 = q1*t27*2.0f;
  150. float t144 = q2*t32*2.0f;
  151. float t145 = q3*t30*2.0f;
  152. float t204 = q0*t28*2.0f;
  153. float t146 = t143+t144+t145-t204;
  154. float t149 = q0*t44*2.0f;
  155. float t150 = q1*t46*2.0f;
  156. float t151 = q2*t41*2.0f;
  157. float t205 = q3*t42*2.0f;
  158. float t152 = t149+t150+t151-t205;
  159. float t155 = q0*t52*2.0f;
  160. float t156 = q1*t54*2.0f;
  161. float t157 = q3*t51*2.0f;
  162. float t206 = q2*t49*2.0f;
  163. float t158 = t155+t156+t157-t206;
  164. float t159 = t69*t79;
  165. float t160 = t71*t75;
  166. float t161 = t159+t160;
  167. float t162 = t69*t80;
  168. float t222 = t71*t78;
  169. float t163 = t162-t222;
  170. float t164 = t78*t79;
  171. float t165 = t75*t80;
  172. float t166 = t164+t165;
  173. float t167 = OP[7][10]*t39;
  174. float t168 = OP[0][10]*t119;
  175. float t193 = OP[1][10]*t123;
  176. float t194 = OP[2][10]*t127;
  177. float t169 = t167+t168-t193-t194;
  178. float t170 = t71*t85;
  179. float t226 = t79*t88;
  180. float t171 = t170-t226;
  181. float t172 = t80*t85;
  182. float t173 = t79*t93;
  183. float t174 = t172+t173;
  184. float t175 = OP[7][9]*t39;
  185. float t176 = OP[0][9]*t119;
  186. float t191 = OP[1][9]*t123;
  187. float t192 = OP[2][9]*t127;
  188. float t177 = t175+t176-t191-t192;
  189. float t178 = OP[7][11]*t39;
  190. float t179 = OP[0][11]*t119;
  191. float t184 = OP[1][11]*t123;
  192. float t185 = OP[2][11]*t127;
  193. float t180 = t178+t179-t184-t185;
  194. float t181 = t71*t93;
  195. float t182 = t80*t88;
  196. float t183 = t181+t182;
  197. float t186 = t71*t98;
  198. float t187 = t80*t99;
  199. float t188 = t186+t187;
  200. float t189 = t79*t98;
  201. float t233 = t80*t102;
  202. float t190 = t189-t233;
  203. float t195 = t71*t102;
  204. float t196 = t79*t99;
  205. float t197 = t195+t196;
  206. float t198 = OP[7][6]*t39;
  207. float t199 = OP[0][6]*t119;
  208. float t200 = OP[7][7]*t39;
  209. float t201 = OP[0][7]*t119;
  210. float t202 = OP[7][8]*t39;
  211. float t203 = OP[0][8]*t119;
  212. float t207 = OP[8][0]*t39;
  213. float t208 = OP[1][0]*t152;
  214. float t216 = OP[0][0]*t146;
  215. float t217 = OP[2][0]*t158;
  216. float t209 = t207+t208-t216-t217;
  217. float t210 = OP[8][1]*t39;
  218. float t211 = OP[1][1]*t152;
  219. float t218 = OP[0][1]*t146;
  220. float t219 = OP[2][1]*t158;
  221. float t212 = t210+t211-t218-t219;
  222. float t213 = OP[8][2]*t39;
  223. float t214 = OP[1][2]*t152;
  224. float t220 = OP[0][2]*t146;
  225. float t221 = OP[2][2]*t158;
  226. float t215 = t213+t214-t220-t221;
  227. float t223 = OP[0][10]*t146;
  228. float t224 = OP[2][10]*t158;
  229. float t236 = OP[8][10]*t39;
  230. float t237 = OP[1][10]*t152;
  231. float t225 = t223+t224-t236-t237;
  232. float t227 = OP[0][9]*t146;
  233. float t228 = OP[2][9]*t158;
  234. float t234 = OP[8][9]*t39;
  235. float t235 = OP[1][9]*t152;
  236. float t229 = t227+t228-t234-t235;
  237. float t230 = OP[0][11]*t146;
  238. float t231 = OP[2][11]*t158;
  239. float t244 = OP[8][11]*t39;
  240. float t245 = OP[1][11]*t152;
  241. float t232 = t230+t231-t244-t245;
  242. float t238 = OP[8][6]*t39;
  243. float t239 = OP[1][6]*t152;
  244. float t240 = OP[8][7]*t39;
  245. float t241 = OP[1][7]*t152;
  246. float t242 = OP[8][8]*t39;
  247. float t243 = OP[1][8]*t152;
  248. float t246 = OP[1][0]*t163;
  249. float t247 = OP[10][0]*t75;
  250. float t248 = OP[0][0]*t166;
  251. float t258 = OP[9][0]*t69;
  252. float t259 = OP[2][0]*t161;
  253. float t260 = OP[11][0]*t78;
  254. float t249 = OP[3][0]+t246+t247+t248-t258-t259-t260;
  255. float t250 = OP[1][1]*t163;
  256. float t251 = OP[10][1]*t75;
  257. float t252 = OP[0][1]*t166;
  258. float t261 = OP[9][1]*t69;
  259. float t262 = OP[2][1]*t161;
  260. float t263 = OP[11][1]*t78;
  261. float t253 = OP[3][1]+t250+t251+t252-t261-t262-t263;
  262. float t254 = OP[1][2]*t163;
  263. float t255 = OP[10][2]*t75;
  264. float t256 = OP[0][2]*t166;
  265. float t264 = OP[9][2]*t69;
  266. float t265 = OP[2][2]*t161;
  267. float t266 = OP[11][2]*t78;
  268. float t257 = OP[3][2]+t254+t255+t256-t264-t265-t266;
  269. float t267 = OP[1][9]*t163;
  270. float t268 = OP[10][9]*t75;
  271. float t269 = OP[0][9]*t166;
  272. float t279 = OP[9][9]*t69;
  273. float t280 = OP[2][9]*t161;
  274. float t281 = OP[11][9]*t78;
  275. float t270 = OP[3][9]+t267+t268+t269-t279-t280-t281;
  276. float t271 = OP[1][11]*t163;
  277. float t272 = OP[10][11]*t75;
  278. float t273 = OP[0][11]*t166;
  279. float t285 = OP[9][11]*t69;
  280. float t286 = OP[2][11]*t161;
  281. float t287 = OP[11][11]*t78;
  282. float t274 = OP[3][11]+t271+t272+t273-t285-t286-t287;
  283. float t275 = OP[1][10]*t163;
  284. float t276 = OP[10][10]*t75;
  285. float t277 = OP[0][10]*t166;
  286. float t282 = OP[9][10]*t69;
  287. float t283 = OP[2][10]*t161;
  288. float t284 = OP[11][10]*t78;
  289. float t278 = OP[3][10]+t275+t276+t277-t282-t283-t284;
  290. float t288 = OP[1][6]*t163;
  291. float t289 = OP[10][6]*t75;
  292. float t290 = OP[0][6]*t166;
  293. float t291 = OP[3][6]+t288+t289+t290-OP[9][6]*t69-OP[2][6]*t161-OP[11][6]*t78;
  294. float t292 = OP[1][7]*t163;
  295. float t293 = OP[10][7]*t75;
  296. float t294 = OP[0][7]*t166;
  297. float t295 = OP[3][7]+t292+t293+t294-OP[9][7]*t69-OP[2][7]*t161-OP[11][7]*t78;
  298. float t296 = OP[1][8]*t163;
  299. float t297 = OP[10][8]*t75;
  300. float t298 = OP[0][8]*t166;
  301. float t299 = OP[3][8]+t296+t297+t298-OP[9][8]*t69-OP[2][8]*t161-OP[11][8]*t78;
  302. float t300 = OP[2][0]*t171;
  303. float t301 = OP[11][0]*t93;
  304. float t302 = OP[1][0]*t183;
  305. float t312 = OP[10][0]*t85;
  306. float t313 = OP[0][0]*t174;
  307. float t314 = OP[9][0]*t88;
  308. float t303 = OP[4][0]+t300+t301+t302-t312-t313-t314;
  309. float t304 = OP[2][1]*t171;
  310. float t305 = OP[11][1]*t93;
  311. float t306 = OP[1][1]*t183;
  312. float t315 = OP[10][1]*t85;
  313. float t316 = OP[0][1]*t174;
  314. float t317 = OP[9][1]*t88;
  315. float t307 = OP[4][1]+t304+t305+t306-t315-t316-t317;
  316. float t308 = OP[2][2]*t171;
  317. float t309 = OP[11][2]*t93;
  318. float t310 = OP[1][2]*t183;
  319. float t318 = OP[10][2]*t85;
  320. float t319 = OP[0][2]*t174;
  321. float t320 = OP[9][2]*t88;
  322. float t311 = OP[4][2]+t308+t309+t310-t318-t319-t320;
  323. float t321 = dvxNoise*t69*t88;
  324. float t322 = OP[2][9]*t171;
  325. float t323 = OP[11][9]*t93;
  326. float t324 = OP[1][9]*t183;
  327. float t334 = OP[10][9]*t85;
  328. float t335 = OP[0][9]*t174;
  329. float t336 = OP[9][9]*t88;
  330. float t325 = OP[4][9]+t322+t323+t324-t334-t335-t336;
  331. float t326 = OP[2][11]*t171;
  332. float t327 = OP[11][11]*t93;
  333. float t328 = OP[1][11]*t183;
  334. float t340 = OP[10][11]*t85;
  335. float t341 = OP[0][11]*t174;
  336. float t342 = OP[9][11]*t88;
  337. float t329 = OP[4][11]+t326+t327+t328-t340-t341-t342;
  338. float t330 = OP[2][10]*t171;
  339. float t331 = OP[11][10]*t93;
  340. float t332 = OP[1][10]*t183;
  341. float t337 = OP[10][10]*t85;
  342. float t338 = OP[0][10]*t174;
  343. float t339 = OP[9][10]*t88;
  344. float t333 = OP[4][10]+t330+t331+t332-t337-t338-t339;
  345. float t343 = OP[2][6]*t171;
  346. float t344 = OP[11][6]*t93;
  347. float t345 = OP[1][6]*t183;
  348. float t346 = OP[4][6]+t343+t344+t345-OP[0][6]*t174-OP[9][6]*t88-OP[10][6]*t85;
  349. float t347 = OP[2][7]*t171;
  350. float t348 = OP[11][7]*t93;
  351. float t349 = OP[1][7]*t183;
  352. float t350 = OP[4][7]+t347+t348+t349-OP[0][7]*t174-OP[9][7]*t88-OP[10][7]*t85;
  353. float t351 = OP[2][8]*t171;
  354. float t352 = OP[11][8]*t93;
  355. float t353 = OP[1][8]*t183;
  356. float t354 = OP[4][8]+t351+t352+t353-OP[0][8]*t174-OP[9][8]*t88-OP[10][8]*t85;
  357. float t355 = OP[0][0]*t190;
  358. float t356 = OP[9][0]*t99;
  359. float t357 = OP[2][0]*t197;
  360. float t367 = OP[11][0]*t98;
  361. float t368 = OP[1][0]*t188;
  362. float t369 = OP[10][0]*t102;
  363. float t358 = OP[5][0]+t355+t356+t357-t367-t368-t369;
  364. float t359 = OP[0][1]*t190;
  365. float t360 = OP[9][1]*t99;
  366. float t361 = OP[2][1]*t197;
  367. float t370 = OP[11][1]*t98;
  368. float t371 = OP[1][1]*t188;
  369. float t372 = OP[10][1]*t102;
  370. float t362 = OP[5][1]+t359+t360+t361-t370-t371-t372;
  371. float t363 = OP[0][2]*t190;
  372. float t364 = OP[9][2]*t99;
  373. float t365 = OP[2][2]*t197;
  374. float t373 = OP[11][2]*t98;
  375. float t374 = OP[1][2]*t188;
  376. float t375 = OP[10][2]*t102;
  377. float t366 = OP[5][2]+t363+t364+t365-t373-t374-t375;
  378. float t376 = dvzNoise*t78*t98;
  379. float t377 = OP[0][9]*t190;
  380. float t378 = OP[9][9]*t99;
  381. float t379 = OP[2][9]*t197;
  382. float t390 = OP[11][9]*t98;
  383. float t391 = OP[1][9]*t188;
  384. float t392 = OP[10][9]*t102;
  385. float t380 = OP[5][9]+t377+t378+t379-t390-t391-t392;
  386. float t381 = OP[0][11]*t190;
  387. float t382 = OP[9][11]*t99;
  388. float t383 = OP[2][11]*t197;
  389. float t396 = OP[11][11]*t98;
  390. float t397 = OP[1][11]*t188;
  391. float t398 = OP[10][11]*t102;
  392. float t384 = OP[5][11]+t381+t382+t383-t396-t397-t398;
  393. float t385 = OP[0][10]*t190;
  394. float t386 = OP[9][10]*t99;
  395. float t387 = OP[2][10]*t197;
  396. float t393 = OP[11][10]*t98;
  397. float t394 = OP[1][10]*t188;
  398. float t395 = OP[10][10]*t102;
  399. float t388 = OP[5][10]+t385+t386+t387-t393-t394-t395;
  400. float t389 = dvyNoise*t85*t102;
  401. float t399 = OP[0][6]*t190;
  402. float t400 = OP[9][6]*t99;
  403. float t401 = OP[2][6]*t197;
  404. float t402 = OP[5][6]+t399+t400+t401-OP[1][6]*t188-OP[10][6]*t102-OP[11][6]*t98;
  405. float t403 = OP[0][7]*t190;
  406. float t404 = OP[9][7]*t99;
  407. float t405 = OP[2][7]*t197;
  408. float t406 = OP[5][7]+t403+t404+t405-OP[1][7]*t188-OP[10][7]*t102-OP[11][7]*t98;
  409. float t407 = OP[0][8]*t190;
  410. float t408 = OP[9][8]*t99;
  411. float t409 = OP[2][8]*t197;
  412. float t410 = OP[5][8]+t407+t408+t409-OP[1][8]*t188-OP[10][8]*t102-OP[11][8]*t98;
  413. A0[0][0] = daxNoise*t140+t34*t61+t48*t68-t56*t70-t39*t107;
  414. A0[0][1] = -t39*t110-t61*t119+t68*t123+t70*t127;
  415. A0[0][2] = -t39*t113-t68*t152+t70*t158+t146*(t59+t60-t66-t67);
  416. A0[0][3] = OP[0][3]*t34+OP[1][3]*t48-OP[2][3]*t56-OP[6][3]*t39+t75*t84-t69*t91-t78*t97-t70*t161+t166*(t59+t60-t66-t67)+t163*(t62+t63-t72-t73);
  417. A0[0][4] = OP[0][4]*t34+OP[1][4]*t48-OP[2][4]*t56-OP[6][4]*t39-t84*t85-t88*t91+t93*t97-t61*t174+t70*t171+t183*(t62+t63-t72-t73);
  418. A0[0][5] = OP[0][5]*t34+OP[1][5]*t48-OP[2][5]*t56-OP[6][5]*t39-t84*t102-t97*t98+t61*t190-t68*t188+t99*(t89+t90-t100-t101)+t197*(t64+t65-t86-t87);
  419. A0[0][6] = t107;
  420. A0[0][7] = t110;
  421. A0[0][8] = t113;
  422. A0[0][9] = t91;
  423. A0[0][10] = t84;
  424. A0[0][11] = t97;
  425. A0[1][0] = -t34*t133-t48*t136+t56*t139+t39*(t198+t199-OP[1][6]*t123-OP[2][6]*t127);
  426. A0[1][1] = dayNoise*t140+t119*t133-t123*t136-t127*t139+t39*(t200+t201-OP[1][7]*t123-OP[2][7]*t127);
  427. A0[1][2] = -t133*t146+t136*t152-t139*t158+t39*(t202+t203-OP[1][8]*t123-OP[2][8]*t127);
  428. A0[1][3] = -OP[7][3]*t39-OP[0][3]*t119+OP[1][3]*t123+OP[2][3]*t127-t75*t169+t69*t177+t78*t180-t133*t166-t136*t163+t139*t161;
  429. A0[1][4] = -OP[7][4]*t39-OP[0][4]*t119+OP[1][4]*t123+OP[2][4]*t127+t85*t169+t88*t177-t93*t180+t133*t174-t139*t171-t136*t183;
  430. A0[1][5] = -OP[7][5]*t39-OP[0][5]*t119+OP[1][5]*t123+OP[2][5]*t127+t102*t169-t99*t177+t98*t180-t133*t190+t136*t188-t139*t197;
  431. A0[1][6] = -t198-t199+OP[1][6]*t123+OP[2][6]*t127;
  432. A0[1][7] = -t200-t201+OP[1][7]*t123+OP[2][7]*t127;
  433. A0[1][8] = -t202-t203+OP[1][8]*t123+OP[2][8]*t127;
  434. A0[1][9] = -t175-t176+t191+t192;
  435. A0[1][10] = -t167-t168+t193+t194;
  436. A0[1][11] = -t178-t179+t184+t185;
  437. A0[2][0] = -t34*t209-t48*t212+t56*t215+t39*(t238+t239-OP[0][6]*t146-OP[2][6]*t158);
  438. A0[2][1] = t119*t209-t123*t212-t127*t215+t39*(t240+t241-OP[0][7]*t146-OP[2][7]*t158);
  439. A0[2][2] = dazNoise*t140-t146*t209+t152*t212-t158*t215+t39*(t242+t243-OP[0][8]*t146-OP[2][8]*t158);
  440. A0[2][3] = -OP[8][3]*t39+OP[0][3]*t146-OP[1][3]*t152+OP[2][3]*t158-t69*t229+t75*t225-t78*t232-t163*t212-t166*t209+t161*t215;
  441. A0[2][4] = -OP[8][4]*t39+OP[0][4]*t146-OP[1][4]*t152+OP[2][4]*t158-t85*t225-t88*t229+t93*t232+t174*t209-t171*t215-t183*t212;
  442. A0[2][5] = -OP[8][5]*t39+OP[0][5]*t146-OP[1][5]*t152+OP[2][5]*t158-t102*t225-t98*t232-t190*t209+t188*t212-t197*t215+t99*(t227+t228-t234-t235);
  443. A0[2][6] = -t238-t239+OP[0][6]*t146+OP[2][6]*t158;
  444. A0[2][7] = -t240-t241+OP[0][7]*t146+OP[2][7]*t158;
  445. A0[2][8] = -t242-t243+OP[0][8]*t146+OP[2][8]*t158;
  446. A0[2][9] = t229;
  447. A0[2][10] = t225;
  448. A0[2][11] = t232;
  449. A0[3][0] = t34*t249+t48*t253-t56*t257-t39*t291;
  450. A0[3][1] = -t39*t295-t119*t249+t123*t253+t127*t257;
  451. A0[3][2] = -t39*t299+t146*t249-t152*t253+t158*t257;
  452. A0[3][3] = OP[3][3]-OP[9][3]*t69+OP[0][3]*t166+OP[1][3]*t163+OP[10][3]*t75-OP[2][3]*t161-OP[11][3]*t78-t69*t270-t78*t274+t75*t278+t166*t249+t163*t253-t161*t257+dvxNoise*(t69*t69)+dvyNoise*(t75*t75)+dvzNoise*(t78*t78);
  453. A0[3][4] = OP[3][4]+t321-OP[9][4]*t69+OP[0][4]*t166+OP[1][4]*t163+OP[10][4]*t75-OP[2][4]*t161-OP[11][4]*t78-t88*t270-t85*t278+t93*t274-t174*t249+t171*t257+t183*t253-dvyNoise*t75*t85-dvzNoise*t78*t93;
  454. A0[3][5] = OP[3][5]+t376-OP[9][5]*t69+OP[0][5]*t166+OP[1][5]*t163+OP[10][5]*t75-OP[2][5]*t161-OP[11][5]*t78+t99*t270-t98*t274-t102*t278+t190*t249-t188*t253+t197*t257-dvxNoise*t69*t99-dvyNoise*t75*t102;
  455. A0[3][6] = t291;
  456. A0[3][7] = t295;
  457. A0[3][8] = t299;
  458. A0[3][9] = t270;
  459. A0[3][10] = t278;
  460. A0[3][11] = t274;
  461. A0[4][0] = t34*t303+t48*t307-t56*t311-t39*t346;
  462. A0[4][1] = -t39*t350-t119*t303+t123*t307+t127*t311;
  463. A0[4][2] = -t39*t354+t146*t303-t152*t307+t158*t311;
  464. A0[4][3] = OP[4][3]+t321-OP[0][3]*t174-OP[9][3]*t88-OP[10][3]*t85+OP[2][3]*t171+OP[1][3]*t183+OP[11][3]*t93-t69*t325-t78*t329+t75*t333+t166*t303+t163*t307-t161*t311-dvyNoise*t75*t85-dvzNoise*t78*t93;
  465. A0[4][4] = OP[4][4]-OP[0][4]*t174-OP[9][4]*t88-OP[10][4]*t85+OP[2][4]*t171+OP[1][4]*t183+OP[11][4]*t93-t88*t325-t85*t333+t93*t329-t174*t303+t171*t311+t183*t307+dvxNoise*(t88*t88)+dvyNoise*(t85*t85)+dvzNoise*(t93*t93);
  466. A0[4][5] = OP[4][5]+t389-OP[0][5]*t174-OP[9][5]*t88-OP[10][5]*t85+OP[2][5]*t171+OP[1][5]*t183+OP[11][5]*t93+t99*t325-t98*t329-t102*t333+t190*t303-t188*t307+t197*t311-dvxNoise*t88*t99-dvzNoise*t93*t98;
  467. A0[4][6] = t346;
  468. A0[4][7] = t350;
  469. A0[4][8] = t354;
  470. A0[4][9] = t325;
  471. A0[4][10] = t333;
  472. A0[4][11] = t329;
  473. A0[5][0] = t34*t358+t48*t362-t56*t366-t39*t402;
  474. A0[5][1] = -t39*t406-t119*t358+t123*t362+t127*t366;
  475. A0[5][2] = -t39*t410+t146*t358-t152*t362+t158*t366;
  476. A0[5][3] = OP[5][3]+t376+OP[9][3]*t99+OP[0][3]*t190-OP[1][3]*t188-OP[10][3]*t102-OP[11][3]*t98+OP[2][3]*t197-t69*t380-t78*t384+t75*t388+t166*t358+t163*t362-t161*t366-dvxNoise*t69*t99-dvyNoise*t75*t102;
  477. A0[5][4] = OP[5][4]+t389+OP[9][4]*t99+OP[0][4]*t190-OP[1][4]*t188-OP[10][4]*t102-OP[11][4]*t98+OP[2][4]*t197-t88*t380-t85*t388+t93*t384-t174*t358+t171*t366+t183*t362-dvxNoise*t88*t99-dvzNoise*t93*t98;
  478. A0[5][5] = OP[5][5]+OP[9][5]*t99+OP[0][5]*t190-OP[1][5]*t188-OP[10][5]*t102-OP[11][5]*t98+OP[2][5]*t197+t99*t380-t98*t384-t102*t388+t190*t358-t188*t362+t197*t366+dvxNoise*(t99*t99)+dvyNoise*(t102*t102)+dvzNoise*(t98*t98);
  479. A0[5][6] = t402;
  480. A0[5][7] = t406;
  481. A0[5][8] = t410;
  482. A0[5][9] = t380;
  483. A0[5][10] = t388;
  484. A0[5][11] = t384;
  485. A0[6][0] = -t411+OP[6][0]*t34+OP[6][1]*t48-OP[6][2]*t56;
  486. A0[6][1] = -t412-OP[6][0]*t119+OP[6][1]*t123+OP[6][2]*t127;
  487. A0[6][2] = -t413+OP[6][0]*t146-OP[6][1]*t152+OP[6][2]*t158;
  488. A0[6][3] = OP[6][3]-OP[6][2]*t161+OP[6][1]*t163+OP[6][0]*t166-OP[6][9]*t69+OP[6][10]*t75-OP[6][11]*t78;
  489. A0[6][4] = OP[6][4]+OP[6][2]*t171-OP[6][0]*t174+OP[6][1]*t183-OP[6][10]*t85-OP[6][9]*t88+OP[6][11]*t93;
  490. A0[6][5] = OP[6][5]-OP[6][1]*t188+OP[6][0]*t190+OP[6][2]*t197+OP[6][9]*t99-OP[6][11]*t98-OP[6][10]*t102;
  491. A0[6][6] = OP[6][6];
  492. A0[6][7] = OP[6][7];
  493. A0[6][8] = OP[6][8];
  494. A0[6][9] = OP[6][9];
  495. A0[6][10] = OP[6][10];
  496. A0[6][11] = OP[6][11];
  497. A0[7][0] = -t198+OP[7][0]*t34+OP[7][1]*t48-OP[7][2]*t56;
  498. A0[7][1] = -t200-OP[7][0]*t119+OP[7][1]*t123+OP[7][2]*t127;
  499. A0[7][2] = -t202+OP[7][0]*t146-OP[7][1]*t152+OP[7][2]*t158;
  500. A0[7][3] = OP[7][3]-OP[7][2]*t161+OP[7][1]*t163+OP[7][0]*t166-OP[7][9]*t69+OP[7][10]*t75-OP[7][11]*t78;
  501. A0[7][4] = OP[7][4]+OP[7][2]*t171-OP[7][0]*t174+OP[7][1]*t183-OP[7][10]*t85-OP[7][9]*t88+OP[7][11]*t93;
  502. A0[7][5] = OP[7][5]-OP[7][1]*t188+OP[7][0]*t190+OP[7][2]*t197+OP[7][9]*t99-OP[7][11]*t98-OP[7][10]*t102;
  503. A0[7][6] = OP[7][6];
  504. A0[7][7] = OP[7][7];
  505. A0[7][8] = OP[7][8];
  506. A0[7][9] = OP[7][9];
  507. A0[7][10] = OP[7][10];
  508. A0[7][11] = OP[7][11];
  509. A0[8][0] = -t238+OP[8][0]*t34+OP[8][1]*t48-OP[8][2]*t56;
  510. A0[8][1] = -t240-OP[8][0]*t119+OP[8][1]*t123+OP[8][2]*t127;
  511. A0[8][2] = -t242+OP[8][0]*t146-OP[8][1]*t152+OP[8][2]*t158;
  512. A0[8][3] = OP[8][3]-OP[8][2]*t161+OP[8][1]*t163+OP[8][0]*t166-OP[8][9]*t69+OP[8][10]*t75-OP[8][11]*t78;
  513. A0[8][4] = OP[8][4]+OP[8][2]*t171-OP[8][0]*t174+OP[8][1]*t183-OP[8][10]*t85-OP[8][9]*t88+OP[8][11]*t93;
  514. A0[8][5] = OP[8][5]-OP[8][1]*t188+OP[8][0]*t190+OP[8][2]*t197+OP[8][9]*t99-OP[8][11]*t98-OP[8][10]*t102;
  515. A0[8][6] = OP[8][6];
  516. A0[8][7] = OP[8][7];
  517. A0[8][8] = OP[8][8];
  518. A0[8][9] = OP[8][9];
  519. A0[8][10] = OP[8][10];
  520. A0[8][11] = OP[8][11];
  521. A0[9][0] = OP[9][0]*t34-OP[9][6]*t39+OP[9][1]*t48-OP[9][2]*t56;
  522. A0[9][1] = -OP[9][7]*t39-OP[9][0]*t119+OP[9][1]*t123+OP[9][2]*t127;
  523. A0[9][2] = -OP[9][8]*t39+OP[9][0]*t146-OP[9][1]*t152+OP[9][2]*t158;
  524. A0[9][3] = OP[9][3]-t279-OP[9][2]*t161+OP[9][1]*t163+OP[9][0]*t166+OP[9][10]*t75-OP[9][11]*t78;
  525. A0[9][4] = OP[9][4]-t336+OP[9][2]*t171-OP[9][0]*t174+OP[9][1]*t183-OP[9][10]*t85+OP[9][11]*t93;
  526. A0[9][5] = OP[9][5]+t378-OP[9][1]*t188+OP[9][0]*t190+OP[9][2]*t197-OP[9][11]*t98-OP[9][10]*t102;
  527. A0[9][6] = OP[9][6];
  528. A0[9][7] = OP[9][7];
  529. A0[9][8] = OP[9][8];
  530. A0[9][9] = OP[9][9];
  531. A0[9][10] = OP[9][10];
  532. A0[9][11] = OP[9][11];
  533. A0[10][0] = OP[10][0]*t34-OP[10][6]*t39+OP[10][1]*t48-OP[10][2]*t56;
  534. A0[10][1] = -OP[10][7]*t39-OP[10][0]*t119+OP[10][1]*t123+OP[10][2]*t127;
  535. A0[10][2] = -OP[10][8]*t39+OP[10][0]*t146-OP[10][1]*t152+OP[10][2]*t158;
  536. A0[10][3] = OP[10][3]+t276-OP[10][2]*t161+OP[10][1]*t163+OP[10][0]*t166-OP[10][9]*t69-OP[10][11]*t78;
  537. A0[10][4] = OP[10][4]-t337+OP[10][2]*t171-OP[10][0]*t174+OP[10][1]*t183-OP[10][9]*t88+OP[10][11]*t93;
  538. A0[10][5] = OP[10][5]-t395-OP[10][1]*t188+OP[10][0]*t190+OP[10][2]*t197+OP[10][9]*t99-OP[10][11]*t98;
  539. A0[10][6] = OP[10][6];
  540. A0[10][7] = OP[10][7];
  541. A0[10][8] = OP[10][8];
  542. A0[10][9] = OP[10][9];
  543. A0[10][10] = OP[10][10];
  544. A0[10][11] = OP[10][11];
  545. A0[11][0] = OP[11][0]*t34-OP[11][6]*t39+OP[11][1]*t48-OP[11][2]*t56;
  546. A0[11][1] = -OP[11][7]*t39-OP[11][0]*t119+OP[11][1]*t123+OP[11][2]*t127;
  547. A0[11][2] = -OP[11][8]*t39+OP[11][0]*t146-OP[11][1]*t152+OP[11][2]*t158;
  548. A0[11][3] = OP[11][3]-t287-OP[11][2]*t161+OP[11][1]*t163+OP[11][0]*t166-OP[11][9]*t69+OP[11][10]*t75;
  549. A0[11][4] = OP[11][4]+t327+OP[11][2]*t171-OP[11][0]*t174+OP[11][1]*t183-OP[11][10]*t85-OP[11][9]*t88;
  550. A0[11][5] = OP[11][5]-t396-OP[11][1]*t188+OP[11][0]*t190+OP[11][2]*t197+OP[11][9]*t99-OP[11][10]*t102;
  551. A0[11][6] = OP[11][6];
  552. A0[11][7] = OP[11][7];
  553. A0[11][8] = OP[11][8];
  554. A0[11][9] = OP[11][9];
  555. A0[11][10] = OP[11][10];
  556. A0[11][11] = OP[11][11];