calcP.txt 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152
  1. SF = zeros(25,1);
  2. SF(1) = daz/2 - daz_b/2;
  3. SF(2) = day/2 - day_b/2;
  4. SF(3) = dax/2 - dax_b/2;
  5. SF(4) = (q0*SF(2))/2 - q2/2 + (q1*SF(1))/2 + (q3*SF(3))/2;
  6. SF(5) = q3/2 + (q0*SF(1))/2 - (q1*SF(2))/2 + (q2*SF(3))/2;
  7. SF(6) = q0/2 + (q1*SF(3))/2 + (q2*SF(2))/2 - (q3*SF(1))/2;
  8. SF(7) = q1/2 - (q0*SF(3))/2 + (q2*SF(1))/2 + (q3*SF(2))/2;
  9. SF(8) = q3/2 - (q0*SF(1))/2 + (q1*SF(2))/2 + (q2*SF(3))/2;
  10. SF(9) = q2/2 + (q0*SF(2))/2 + (q1*SF(1))/2 - (q3*SF(3))/2;
  11. SF(10) = (q0*SF(3))/2 - q1/2 + (q2*SF(1))/2 + (q3*SF(2))/2;
  12. SF(11) = q0/2 + (q1*SF(3))/2 - (q2*SF(2))/2 + (q3*SF(1))/2;
  13. SF(12) = q0/2 - (q1*SF(3))/2 + (q2*SF(2))/2 + (q3*SF(1))/2;
  14. SF(13) = q1/2 + (q0*SF(3))/2 - (q2*SF(1))/2 + (q3*SF(2))/2;
  15. SF(14) = q2/2 - (q0*SF(2))/2 + (q1*SF(1))/2 + (q3*SF(3))/2;
  16. SF(15) = (q0*SF(1))/2 - q3/2 + (q1*SF(2))/2 + (q2*SF(3))/2;
  17. SF(16) = - q0^2 - q1^2 - q2^2 - q3^2;
  18. SF(17) = q0^2 - q1^2 - q2^2 + q3^2;
  19. SF(18) = q0^2 - q1^2 + q2^2 - q3^2;
  20. SF(19) = q0^2 + q1^2 - q2^2 - q3^2;
  21. SF(20) = 2*q0*q2 - 2*q1*q3;
  22. SF(21) = 2*q0*q1 - 2*q2*q3;
  23. SF(22) = 2*q0*q3 - 2*q1*q2;
  24. SF(23) = 2*q0*q1 + 2*q2*q3;
  25. SF(24) = 2*q0*q3 + 2*q1*q2;
  26. SF(25) = 2*q0*q2 + 2*q1*q3;
  27. SG = zeros(5,1);
  28. SG(1) = - q0^2 - q1^2 - q2^2 - q3^2;
  29. SG(2) = q3^2;
  30. SG(3) = q2^2;
  31. SG(4) = q1^2;
  32. SG(5) = q0^2;
  33. SQ = zeros(8,1);
  34. SQ(1) = dvyNoise*(2*q0*q1 + 2*q2*q3)*(q0^2 - q1^2 + q2^2 - q3^2) - dvzNoise*(2*q0*q1 - 2*q2*q3)*(q0^2 - q1^2 - q2^2 + q3^2) - dvxNoise*(2*q0*q2 - 2*q1*q3)*(2*q0*q3 + 2*q1*q2);
  35. SQ(2) = dvzNoise*(2*q0*q2 + 2*q1*q3)*(q0^2 - q1^2 - q2^2 + q3^2) - dvxNoise*(2*q0*q2 - 2*q1*q3)*(q0^2 + q1^2 - q2^2 - q3^2) - dvyNoise*(2*q0*q1 + 2*q2*q3)*(2*q0*q3 - 2*q1*q2);
  36. SQ(3) = dvxNoise*(2*q0*q3 + 2*q1*q2)*(q0^2 + q1^2 - q2^2 - q3^2) - dvyNoise*(2*q0*q3 - 2*q1*q2)*(q0^2 - q1^2 + q2^2 - q3^2) - dvzNoise*(2*q0*q1 - 2*q2*q3)*(2*q0*q2 + 2*q1*q3);
  37. SQ(4) = (q0^2 + q1^2 + q2^2 + q3^2)^2;
  38. SQ(5) = q3^2;
  39. SQ(6) = q2^2;
  40. SQ(7) = q1^2;
  41. SQ(8) = q0^2;
  42. SPP = zeros(19,1);
  43. SPP(1) = 2*q2*SF(12) - 2*q0*SF(14) + 2*q1*SF(15) + 2*q3*SF(13);
  44. SPP(2) = 2*q0*SF(10) + 2*q2*SF(8) + 2*q1*SF(11) - 2*q3*SF(9);
  45. SPP(3) = 2*q0*SF(15) + 2*q1*SF(14) - 2*q2*SF(13) + 2*q3*SF(12);
  46. SPP(4) = 2*q0*SF(11) - 2*q1*SF(10) + 2*q2*SF(9) + 2*q3*SF(8);
  47. SPP(5) = 2*q0*SF(12) + 2*q1*SF(13) + 2*q2*SF(14) - 2*q3*SF(15);
  48. SPP(6) = 2*q1*SF(9) - 2*q0*SF(8) + 2*q2*SF(10) + 2*q3*SF(11);
  49. SPP(7) = 2*q0*SF(6) - 2*q2*SF(4) + 2*q1*SF(7) + 2*q3*SF(5);
  50. SPP(8) = 2*q1*SF(6) - 2*q0*SF(7) + 2*q2*SF(5) + 2*q3*SF(4);
  51. SPP(9) = 2*q0*SF(4) - 2*q1*SF(5) + 2*q2*SF(6) + 2*q3*SF(7);
  52. SPP(10) = dvy*SF(17) - dvz*SF(23);
  53. SPP(11) = dvx*SF(18) - dvy*SF(24);
  54. SPP(12) = dvx*SF(25) - dvz*SF(19);
  55. SPP(13) = dvx*SF(17) + dvz*SF(20);
  56. SPP(14) = dvx*SF(23) + dvy*SF(20);
  57. SPP(15) = dvy*SF(21) + dvz*SF(18);
  58. SPP(16) = dvx*SF(21) + dvz*SF(24);
  59. SPP(17) = dvy*SF(25) + dvz*SF(22);
  60. SPP(18) = dvx*SF(22) + dvy*SF(19);
  61. SPP(19) = SF(16);
  62. nextP = zeros(9,9);
  63. nextP(1,1) = daxNoise*SQ(4) + SPP(5)*(OP_l_1_c_1_r_*SPP(5) + OP_l_2_c_1_r_*SPP(6) - OP_l_3_c_1_r_*SPP(9) + OP_l_7_c_1_r_*SPP(19)) + SPP(6)*(OP_l_1_c_2_r_*SPP(5) + OP_l_2_c_2_r_*SPP(6) - OP_l_3_c_2_r_*SPP(9) + OP_l_7_c_2_r_*SPP(19)) - SPP(9)*(OP_l_1_c_3_r_*SPP(5) + OP_l_2_c_3_r_*SPP(6) - OP_l_3_c_3_r_*SPP(9) + OP_l_7_c_3_r_*SPP(19)) + SPP(19)*(OP_l_1_c_7_r_*SPP(5) + OP_l_2_c_7_r_*SPP(6) - OP_l_3_c_7_r_*SPP(9) + OP_l_7_c_7_r_*SPP(19));
  64. nextP(1,2) = SPP(4)*(OP_l_1_c_2_r_*SPP(5) + OP_l_2_c_2_r_*SPP(6) - OP_l_3_c_2_r_*SPP(9) + OP_l_7_c_2_r_*SPP(19)) - SPP(3)*(OP_l_1_c_1_r_*SPP(5) + OP_l_2_c_1_r_*SPP(6) - OP_l_3_c_1_r_*SPP(9) + OP_l_7_c_1_r_*SPP(19)) + SPP(8)*(OP_l_1_c_3_r_*SPP(5) + OP_l_2_c_3_r_*SPP(6) - OP_l_3_c_3_r_*SPP(9) + OP_l_7_c_3_r_*SPP(19)) + SPP(19)*(OP_l_1_c_8_r_*SPP(5) + OP_l_2_c_8_r_*SPP(6) - OP_l_3_c_8_r_*SPP(9) + OP_l_7_c_8_r_*SPP(19));
  65. nextP(1,3) = SPP(1)*(OP_l_1_c_1_r_*SPP(5) + OP_l_2_c_1_r_*SPP(6) - OP_l_3_c_1_r_*SPP(9) + OP_l_7_c_1_r_*SPP(19)) - SPP(2)*(OP_l_1_c_2_r_*SPP(5) + OP_l_2_c_2_r_*SPP(6) - OP_l_3_c_2_r_*SPP(9) + OP_l_7_c_2_r_*SPP(19)) + SPP(7)*(OP_l_1_c_3_r_*SPP(5) + OP_l_2_c_3_r_*SPP(6) - OP_l_3_c_3_r_*SPP(9) + OP_l_7_c_3_r_*SPP(19)) + SPP(19)*(OP_l_1_c_9_r_*SPP(5) + OP_l_2_c_9_r_*SPP(6) - OP_l_3_c_9_r_*SPP(9) + OP_l_7_c_9_r_*SPP(19));
  66. nextP(1,4) = OP_l_1_c_4_r_*SPP(5) + OP_l_2_c_4_r_*SPP(6) - OP_l_3_c_4_r_*SPP(9) + OP_l_7_c_4_r_*SPP(19) - SPP(12)*(OP_l_1_c_2_r_*SPP(5) + OP_l_2_c_2_r_*SPP(6) - OP_l_3_c_2_r_*SPP(9) + OP_l_7_c_2_r_*SPP(19)) + SPP(17)*(OP_l_1_c_1_r_*SPP(5) + OP_l_2_c_1_r_*SPP(6) - OP_l_3_c_1_r_*SPP(9) + OP_l_7_c_1_r_*SPP(19)) - SPP(18)*(OP_l_1_c_3_r_*SPP(5) + OP_l_2_c_3_r_*SPP(6) - OP_l_3_c_3_r_*SPP(9) + OP_l_7_c_3_r_*SPP(19));
  67. nextP(1,5) = OP_l_1_c_5_r_*SPP(5) + OP_l_2_c_5_r_*SPP(6) - OP_l_3_c_5_r_*SPP(9) + OP_l_7_c_5_r_*SPP(19) - SPP(15)*(OP_l_1_c_1_r_*SPP(5) + OP_l_2_c_1_r_*SPP(6) - OP_l_3_c_1_r_*SPP(9) + OP_l_7_c_1_r_*SPP(19)) + SPP(11)*(OP_l_1_c_3_r_*SPP(5) + OP_l_2_c_3_r_*SPP(6) - OP_l_3_c_3_r_*SPP(9) + OP_l_7_c_3_r_*SPP(19)) + SPP(16)*(OP_l_1_c_2_r_*SPP(5) + OP_l_2_c_2_r_*SPP(6) - OP_l_3_c_2_r_*SPP(9) + OP_l_7_c_2_r_*SPP(19));
  68. nextP(1,6) = OP_l_1_c_6_r_*SPP(5) + OP_l_2_c_6_r_*SPP(6) - OP_l_3_c_6_r_*SPP(9) + OP_l_7_c_6_r_*SPP(19) + SPP(10)*(OP_l_1_c_1_r_*SPP(5) + OP_l_2_c_1_r_*SPP(6) - OP_l_3_c_1_r_*SPP(9) + OP_l_7_c_1_r_*SPP(19)) - SPP(13)*(OP_l_1_c_2_r_*SPP(5) + OP_l_2_c_2_r_*SPP(6) - OP_l_3_c_2_r_*SPP(9) + OP_l_7_c_2_r_*SPP(19)) + SPP(14)*(OP_l_1_c_3_r_*SPP(5) + OP_l_2_c_3_r_*SPP(6) - OP_l_3_c_3_r_*SPP(9) + OP_l_7_c_3_r_*SPP(19));
  69. nextP(1,7) = OP_l_1_c_7_r_*SPP(5) + OP_l_2_c_7_r_*SPP(6) - OP_l_3_c_7_r_*SPP(9) + OP_l_7_c_7_r_*SPP(19);
  70. nextP(1,8) = OP_l_1_c_8_r_*SPP(5) + OP_l_2_c_8_r_*SPP(6) - OP_l_3_c_8_r_*SPP(9) + OP_l_7_c_8_r_*SPP(19);
  71. nextP(1,9) = OP_l_1_c_9_r_*SPP(5) + OP_l_2_c_9_r_*SPP(6) - OP_l_3_c_9_r_*SPP(9) + OP_l_7_c_9_r_*SPP(19);
  72. nextP(2,1) = SPP(5)*(OP_l_2_c_1_r_*SPP(4) - OP_l_1_c_1_r_*SPP(3) + OP_l_3_c_1_r_*SPP(8) + OP_l_8_c_1_r_*SPP(19)) + SPP(6)*(OP_l_2_c_2_r_*SPP(4) - OP_l_1_c_2_r_*SPP(3) + OP_l_3_c_2_r_*SPP(8) + OP_l_8_c_2_r_*SPP(19)) - SPP(9)*(OP_l_2_c_3_r_*SPP(4) - OP_l_1_c_3_r_*SPP(3) + OP_l_3_c_3_r_*SPP(8) + OP_l_8_c_3_r_*SPP(19)) + SPP(19)*(OP_l_2_c_7_r_*SPP(4) - OP_l_1_c_7_r_*SPP(3) + OP_l_3_c_7_r_*SPP(8) + OP_l_8_c_7_r_*SPP(19));
  73. nextP(2,2) = dayNoise*SQ(4) - SPP(3)*(OP_l_2_c_1_r_*SPP(4) - OP_l_1_c_1_r_*SPP(3) + OP_l_3_c_1_r_*SPP(8) + OP_l_8_c_1_r_*SPP(19)) + SPP(4)*(OP_l_2_c_2_r_*SPP(4) - OP_l_1_c_2_r_*SPP(3) + OP_l_3_c_2_r_*SPP(8) + OP_l_8_c_2_r_*SPP(19)) + SPP(8)*(OP_l_2_c_3_r_*SPP(4) - OP_l_1_c_3_r_*SPP(3) + OP_l_3_c_3_r_*SPP(8) + OP_l_8_c_3_r_*SPP(19)) + SPP(19)*(OP_l_2_c_8_r_*SPP(4) - OP_l_1_c_8_r_*SPP(3) + OP_l_3_c_8_r_*SPP(8) + OP_l_8_c_8_r_*SPP(19));
  74. nextP(2,3) = SPP(1)*(OP_l_2_c_1_r_*SPP(4) - OP_l_1_c_1_r_*SPP(3) + OP_l_3_c_1_r_*SPP(8) + OP_l_8_c_1_r_*SPP(19)) - SPP(2)*(OP_l_2_c_2_r_*SPP(4) - OP_l_1_c_2_r_*SPP(3) + OP_l_3_c_2_r_*SPP(8) + OP_l_8_c_2_r_*SPP(19)) + SPP(7)*(OP_l_2_c_3_r_*SPP(4) - OP_l_1_c_3_r_*SPP(3) + OP_l_3_c_3_r_*SPP(8) + OP_l_8_c_3_r_*SPP(19)) + SPP(19)*(OP_l_2_c_9_r_*SPP(4) - OP_l_1_c_9_r_*SPP(3) + OP_l_3_c_9_r_*SPP(8) + OP_l_8_c_9_r_*SPP(19));
  75. nextP(2,4) = OP_l_2_c_4_r_*SPP(4) - OP_l_1_c_4_r_*SPP(3) + OP_l_3_c_4_r_*SPP(8) + OP_l_8_c_4_r_*SPP(19) - SPP(12)*(OP_l_2_c_2_r_*SPP(4) - OP_l_1_c_2_r_*SPP(3) + OP_l_3_c_2_r_*SPP(8) + OP_l_8_c_2_r_*SPP(19)) + SPP(17)*(OP_l_2_c_1_r_*SPP(4) - OP_l_1_c_1_r_*SPP(3) + OP_l_3_c_1_r_*SPP(8) + OP_l_8_c_1_r_*SPP(19)) - SPP(18)*(OP_l_2_c_3_r_*SPP(4) - OP_l_1_c_3_r_*SPP(3) + OP_l_3_c_3_r_*SPP(8) + OP_l_8_c_3_r_*SPP(19));
  76. nextP(2,5) = OP_l_2_c_5_r_*SPP(4) - OP_l_1_c_5_r_*SPP(3) + OP_l_3_c_5_r_*SPP(8) + OP_l_8_c_5_r_*SPP(19) - SPP(15)*(OP_l_2_c_1_r_*SPP(4) - OP_l_1_c_1_r_*SPP(3) + OP_l_3_c_1_r_*SPP(8) + OP_l_8_c_1_r_*SPP(19)) + SPP(11)*(OP_l_2_c_3_r_*SPP(4) - OP_l_1_c_3_r_*SPP(3) + OP_l_3_c_3_r_*SPP(8) + OP_l_8_c_3_r_*SPP(19)) + SPP(16)*(OP_l_2_c_2_r_*SPP(4) - OP_l_1_c_2_r_*SPP(3) + OP_l_3_c_2_r_*SPP(8) + OP_l_8_c_2_r_*SPP(19));
  77. nextP(2,6) = OP_l_2_c_6_r_*SPP(4) - OP_l_1_c_6_r_*SPP(3) + OP_l_3_c_6_r_*SPP(8) + OP_l_8_c_6_r_*SPP(19) + SPP(10)*(OP_l_2_c_1_r_*SPP(4) - OP_l_1_c_1_r_*SPP(3) + OP_l_3_c_1_r_*SPP(8) + OP_l_8_c_1_r_*SPP(19)) - SPP(13)*(OP_l_2_c_2_r_*SPP(4) - OP_l_1_c_2_r_*SPP(3) + OP_l_3_c_2_r_*SPP(8) + OP_l_8_c_2_r_*SPP(19)) + SPP(14)*(OP_l_2_c_3_r_*SPP(4) - OP_l_1_c_3_r_*SPP(3) + OP_l_3_c_3_r_*SPP(8) + OP_l_8_c_3_r_*SPP(19));
  78. nextP(2,7) = OP_l_2_c_7_r_*SPP(4) - OP_l_1_c_7_r_*SPP(3) + OP_l_3_c_7_r_*SPP(8) + OP_l_8_c_7_r_*SPP(19);
  79. nextP(2,8) = OP_l_2_c_8_r_*SPP(4) - OP_l_1_c_8_r_*SPP(3) + OP_l_3_c_8_r_*SPP(8) + OP_l_8_c_8_r_*SPP(19);
  80. nextP(2,9) = OP_l_2_c_9_r_*SPP(4) - OP_l_1_c_9_r_*SPP(3) + OP_l_3_c_9_r_*SPP(8) + OP_l_8_c_9_r_*SPP(19);
  81. nextP(3,1) = SPP(5)*(OP_l_1_c_1_r_*SPP(1) - OP_l_2_c_1_r_*SPP(2) + OP_l_3_c_1_r_*SPP(7) + OP_l_9_c_1_r_*SPP(19)) + SPP(6)*(OP_l_1_c_2_r_*SPP(1) - OP_l_2_c_2_r_*SPP(2) + OP_l_3_c_2_r_*SPP(7) + OP_l_9_c_2_r_*SPP(19)) - SPP(9)*(OP_l_1_c_3_r_*SPP(1) - OP_l_2_c_3_r_*SPP(2) + OP_l_3_c_3_r_*SPP(7) + OP_l_9_c_3_r_*SPP(19)) + SPP(19)*(OP_l_1_c_7_r_*SPP(1) - OP_l_2_c_7_r_*SPP(2) + OP_l_3_c_7_r_*SPP(7) + OP_l_9_c_7_r_*SPP(19));
  82. nextP(3,2) = SPP(4)*(OP_l_1_c_2_r_*SPP(1) - OP_l_2_c_2_r_*SPP(2) + OP_l_3_c_2_r_*SPP(7) + OP_l_9_c_2_r_*SPP(19)) - SPP(3)*(OP_l_1_c_1_r_*SPP(1) - OP_l_2_c_1_r_*SPP(2) + OP_l_3_c_1_r_*SPP(7) + OP_l_9_c_1_r_*SPP(19)) + SPP(8)*(OP_l_1_c_3_r_*SPP(1) - OP_l_2_c_3_r_*SPP(2) + OP_l_3_c_3_r_*SPP(7) + OP_l_9_c_3_r_*SPP(19)) + SPP(19)*(OP_l_1_c_8_r_*SPP(1) - OP_l_2_c_8_r_*SPP(2) + OP_l_3_c_8_r_*SPP(7) + OP_l_9_c_8_r_*SPP(19));
  83. nextP(3,3) = dazNoise*SQ(4) + SPP(1)*(OP_l_1_c_1_r_*SPP(1) - OP_l_2_c_1_r_*SPP(2) + OP_l_3_c_1_r_*SPP(7) + OP_l_9_c_1_r_*SPP(19)) - SPP(2)*(OP_l_1_c_2_r_*SPP(1) - OP_l_2_c_2_r_*SPP(2) + OP_l_3_c_2_r_*SPP(7) + OP_l_9_c_2_r_*SPP(19)) + SPP(7)*(OP_l_1_c_3_r_*SPP(1) - OP_l_2_c_3_r_*SPP(2) + OP_l_3_c_3_r_*SPP(7) + OP_l_9_c_3_r_*SPP(19)) + SPP(19)*(OP_l_1_c_9_r_*SPP(1) - OP_l_2_c_9_r_*SPP(2) + OP_l_3_c_9_r_*SPP(7) + OP_l_9_c_9_r_*SPP(19));
  84. nextP(3,4) = OP_l_1_c_4_r_*SPP(1) - OP_l_2_c_4_r_*SPP(2) + OP_l_3_c_4_r_*SPP(7) + OP_l_9_c_4_r_*SPP(19) - SPP(12)*(OP_l_1_c_2_r_*SPP(1) - OP_l_2_c_2_r_*SPP(2) + OP_l_3_c_2_r_*SPP(7) + OP_l_9_c_2_r_*SPP(19)) + SPP(17)*(OP_l_1_c_1_r_*SPP(1) - OP_l_2_c_1_r_*SPP(2) + OP_l_3_c_1_r_*SPP(7) + OP_l_9_c_1_r_*SPP(19)) - SPP(18)*(OP_l_1_c_3_r_*SPP(1) - OP_l_2_c_3_r_*SPP(2) + OP_l_3_c_3_r_*SPP(7) + OP_l_9_c_3_r_*SPP(19));
  85. nextP(3,5) = OP_l_1_c_5_r_*SPP(1) - OP_l_2_c_5_r_*SPP(2) + OP_l_3_c_5_r_*SPP(7) + OP_l_9_c_5_r_*SPP(19) - SPP(15)*(OP_l_1_c_1_r_*SPP(1) - OP_l_2_c_1_r_*SPP(2) + OP_l_3_c_1_r_*SPP(7) + OP_l_9_c_1_r_*SPP(19)) + SPP(11)*(OP_l_1_c_3_r_*SPP(1) - OP_l_2_c_3_r_*SPP(2) + OP_l_3_c_3_r_*SPP(7) + OP_l_9_c_3_r_*SPP(19)) + SPP(16)*(OP_l_1_c_2_r_*SPP(1) - OP_l_2_c_2_r_*SPP(2) + OP_l_3_c_2_r_*SPP(7) + OP_l_9_c_2_r_*SPP(19));
  86. nextP(3,6) = OP_l_1_c_6_r_*SPP(1) - OP_l_2_c_6_r_*SPP(2) + OP_l_3_c_6_r_*SPP(7) + OP_l_9_c_6_r_*SPP(19) + SPP(10)*(OP_l_1_c_1_r_*SPP(1) - OP_l_2_c_1_r_*SPP(2) + OP_l_3_c_1_r_*SPP(7) + OP_l_9_c_1_r_*SPP(19)) - SPP(13)*(OP_l_1_c_2_r_*SPP(1) - OP_l_2_c_2_r_*SPP(2) + OP_l_3_c_2_r_*SPP(7) + OP_l_9_c_2_r_*SPP(19)) + SPP(14)*(OP_l_1_c_3_r_*SPP(1) - OP_l_2_c_3_r_*SPP(2) + OP_l_3_c_3_r_*SPP(7) + OP_l_9_c_3_r_*SPP(19));
  87. nextP(3,7) = OP_l_1_c_7_r_*SPP(1) - OP_l_2_c_7_r_*SPP(2) + OP_l_3_c_7_r_*SPP(7) + OP_l_9_c_7_r_*SPP(19);
  88. nextP(3,8) = OP_l_1_c_8_r_*SPP(1) - OP_l_2_c_8_r_*SPP(2) + OP_l_3_c_8_r_*SPP(7) + OP_l_9_c_8_r_*SPP(19);
  89. nextP(3,9) = OP_l_1_c_9_r_*SPP(1) - OP_l_2_c_9_r_*SPP(2) + OP_l_3_c_9_r_*SPP(7) + OP_l_9_c_9_r_*SPP(19);
  90. nextP(4,1) = SPP(5)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SPP(17) - OP_l_2_c_1_r_*SPP(12) - OP_l_3_c_1_r_*SPP(18)) + SPP(6)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SPP(17) - OP_l_2_c_2_r_*SPP(12) - OP_l_3_c_2_r_*SPP(18)) - SPP(9)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SPP(17) - OP_l_2_c_3_r_*SPP(12) - OP_l_3_c_3_r_*SPP(18)) + SPP(19)*(OP_l_4_c_7_r_ + OP_l_1_c_7_r_*SPP(17) - OP_l_2_c_7_r_*SPP(12) - OP_l_3_c_7_r_*SPP(18));
  91. nextP(4,2) = SPP(4)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SPP(17) - OP_l_2_c_2_r_*SPP(12) - OP_l_3_c_2_r_*SPP(18)) - SPP(3)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SPP(17) - OP_l_2_c_1_r_*SPP(12) - OP_l_3_c_1_r_*SPP(18)) + SPP(8)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SPP(17) - OP_l_2_c_3_r_*SPP(12) - OP_l_3_c_3_r_*SPP(18)) + SPP(19)*(OP_l_4_c_8_r_ + OP_l_1_c_8_r_*SPP(17) - OP_l_2_c_8_r_*SPP(12) - OP_l_3_c_8_r_*SPP(18));
  92. nextP(4,3) = SPP(1)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SPP(17) - OP_l_2_c_1_r_*SPP(12) - OP_l_3_c_1_r_*SPP(18)) - SPP(2)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SPP(17) - OP_l_2_c_2_r_*SPP(12) - OP_l_3_c_2_r_*SPP(18)) + SPP(7)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SPP(17) - OP_l_2_c_3_r_*SPP(12) - OP_l_3_c_3_r_*SPP(18)) + SPP(19)*(OP_l_4_c_9_r_ + OP_l_1_c_9_r_*SPP(17) - OP_l_2_c_9_r_*SPP(12) - OP_l_3_c_9_r_*SPP(18));
  93. nextP(4,4) = OP_l_4_c_4_r_ + OP_l_1_c_4_r_*SPP(17) - OP_l_2_c_4_r_*SPP(12) - OP_l_3_c_4_r_*SPP(18) + dvyNoise*(2*q0*q3 - 2*q1*q2)^2 + dvzNoise*(2*q0*q2 + 2*q1*q3)^2 - SPP(12)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SPP(17) - OP_l_2_c_2_r_*SPP(12) - OP_l_3_c_2_r_*SPP(18)) + SPP(17)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SPP(17) - OP_l_2_c_1_r_*SPP(12) - OP_l_3_c_1_r_*SPP(18)) - SPP(18)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SPP(17) - OP_l_2_c_3_r_*SPP(12) - OP_l_3_c_3_r_*SPP(18)) + dvxNoise*(SQ(5) + SQ(6) - SQ(7) - SQ(8))^2;
  94. nextP(4,5) = OP_l_4_c_5_r_ + SQ(3) + OP_l_1_c_5_r_*SPP(17) - OP_l_2_c_5_r_*SPP(12) - OP_l_3_c_5_r_*SPP(18) - SPP(15)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SPP(17) - OP_l_2_c_1_r_*SPP(12) - OP_l_3_c_1_r_*SPP(18)) + SPP(11)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SPP(17) - OP_l_2_c_3_r_*SPP(12) - OP_l_3_c_3_r_*SPP(18)) + SPP(16)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SPP(17) - OP_l_2_c_2_r_*SPP(12) - OP_l_3_c_2_r_*SPP(18));
  95. nextP(4,6) = OP_l_4_c_6_r_ + SQ(2) + OP_l_1_c_6_r_*SPP(17) - OP_l_2_c_6_r_*SPP(12) - OP_l_3_c_6_r_*SPP(18) + SPP(10)*(OP_l_4_c_1_r_ + OP_l_1_c_1_r_*SPP(17) - OP_l_2_c_1_r_*SPP(12) - OP_l_3_c_1_r_*SPP(18)) - SPP(13)*(OP_l_4_c_2_r_ + OP_l_1_c_2_r_*SPP(17) - OP_l_2_c_2_r_*SPP(12) - OP_l_3_c_2_r_*SPP(18)) + SPP(14)*(OP_l_4_c_3_r_ + OP_l_1_c_3_r_*SPP(17) - OP_l_2_c_3_r_*SPP(12) - OP_l_3_c_3_r_*SPP(18));
  96. nextP(4,7) = OP_l_4_c_7_r_ + OP_l_1_c_7_r_*SPP(17) - OP_l_2_c_7_r_*SPP(12) - OP_l_3_c_7_r_*SPP(18);
  97. nextP(4,8) = OP_l_4_c_8_r_ + OP_l_1_c_8_r_*SPP(17) - OP_l_2_c_8_r_*SPP(12) - OP_l_3_c_8_r_*SPP(18);
  98. nextP(4,9) = OP_l_4_c_9_r_ + OP_l_1_c_9_r_*SPP(17) - OP_l_2_c_9_r_*SPP(12) - OP_l_3_c_9_r_*SPP(18);
  99. nextP(5,1) = SPP(5)*(OP_l_5_c_1_r_ - OP_l_1_c_1_r_*SPP(15) + OP_l_2_c_1_r_*SPP(16) + OP_l_3_c_1_r_*SPP(11)) + SPP(6)*(OP_l_5_c_2_r_ - OP_l_1_c_2_r_*SPP(15) + OP_l_2_c_2_r_*SPP(16) + OP_l_3_c_2_r_*SPP(11)) - SPP(9)*(OP_l_5_c_3_r_ - OP_l_1_c_3_r_*SPP(15) + OP_l_2_c_3_r_*SPP(16) + OP_l_3_c_3_r_*SPP(11)) + SPP(19)*(OP_l_5_c_7_r_ - OP_l_1_c_7_r_*SPP(15) + OP_l_2_c_7_r_*SPP(16) + OP_l_3_c_7_r_*SPP(11));
  100. nextP(5,2) = SPP(4)*(OP_l_5_c_2_r_ - OP_l_1_c_2_r_*SPP(15) + OP_l_2_c_2_r_*SPP(16) + OP_l_3_c_2_r_*SPP(11)) - SPP(3)*(OP_l_5_c_1_r_ - OP_l_1_c_1_r_*SPP(15) + OP_l_2_c_1_r_*SPP(16) + OP_l_3_c_1_r_*SPP(11)) + SPP(8)*(OP_l_5_c_3_r_ - OP_l_1_c_3_r_*SPP(15) + OP_l_2_c_3_r_*SPP(16) + OP_l_3_c_3_r_*SPP(11)) + SPP(19)*(OP_l_5_c_8_r_ - OP_l_1_c_8_r_*SPP(15) + OP_l_2_c_8_r_*SPP(16) + OP_l_3_c_8_r_*SPP(11));
  101. nextP(5,3) = SPP(1)*(OP_l_5_c_1_r_ - OP_l_1_c_1_r_*SPP(15) + OP_l_2_c_1_r_*SPP(16) + OP_l_3_c_1_r_*SPP(11)) - SPP(2)*(OP_l_5_c_2_r_ - OP_l_1_c_2_r_*SPP(15) + OP_l_2_c_2_r_*SPP(16) + OP_l_3_c_2_r_*SPP(11)) + SPP(7)*(OP_l_5_c_3_r_ - OP_l_1_c_3_r_*SPP(15) + OP_l_2_c_3_r_*SPP(16) + OP_l_3_c_3_r_*SPP(11)) + SPP(19)*(OP_l_5_c_9_r_ - OP_l_1_c_9_r_*SPP(15) + OP_l_2_c_9_r_*SPP(16) + OP_l_3_c_9_r_*SPP(11));
  102. nextP(5,4) = OP_l_5_c_4_r_ + SQ(3) - OP_l_1_c_4_r_*SPP(15) + OP_l_2_c_4_r_*SPP(16) + OP_l_3_c_4_r_*SPP(11) - SPP(12)*(OP_l_5_c_2_r_ - OP_l_1_c_2_r_*SPP(15) + OP_l_2_c_2_r_*SPP(16) + OP_l_3_c_2_r_*SPP(11)) + SPP(17)*(OP_l_5_c_1_r_ - OP_l_1_c_1_r_*SPP(15) + OP_l_2_c_1_r_*SPP(16) + OP_l_3_c_1_r_*SPP(11)) - SPP(18)*(OP_l_5_c_3_r_ - OP_l_1_c_3_r_*SPP(15) + OP_l_2_c_3_r_*SPP(16) + OP_l_3_c_3_r_*SPP(11));
  103. nextP(5,5) = OP_l_5_c_5_r_ - OP_l_1_c_5_r_*SPP(15) + OP_l_2_c_5_r_*SPP(16) + OP_l_3_c_5_r_*SPP(11) + dvxNoise*(2*q0*q3 + 2*q1*q2)^2 + dvzNoise*(2*q0*q1 - 2*q2*q3)^2 - SPP(15)*(OP_l_5_c_1_r_ - OP_l_1_c_1_r_*SPP(15) + OP_l_2_c_1_r_*SPP(16) + OP_l_3_c_1_r_*SPP(11)) + SPP(11)*(OP_l_5_c_3_r_ - OP_l_1_c_3_r_*SPP(15) + OP_l_2_c_3_r_*SPP(16) + OP_l_3_c_3_r_*SPP(11)) + SPP(16)*(OP_l_5_c_2_r_ - OP_l_1_c_2_r_*SPP(15) + OP_l_2_c_2_r_*SPP(16) + OP_l_3_c_2_r_*SPP(11)) + dvyNoise*(SQ(5) - SQ(6) + SQ(7) - SQ(8))^2;
  104. nextP(5,6) = OP_l_5_c_6_r_ + SQ(1) - OP_l_1_c_6_r_*SPP(15) + OP_l_2_c_6_r_*SPP(16) + OP_l_3_c_6_r_*SPP(11) + SPP(10)*(OP_l_5_c_1_r_ - OP_l_1_c_1_r_*SPP(15) + OP_l_2_c_1_r_*SPP(16) + OP_l_3_c_1_r_*SPP(11)) - SPP(13)*(OP_l_5_c_2_r_ - OP_l_1_c_2_r_*SPP(15) + OP_l_2_c_2_r_*SPP(16) + OP_l_3_c_2_r_*SPP(11)) + SPP(14)*(OP_l_5_c_3_r_ - OP_l_1_c_3_r_*SPP(15) + OP_l_2_c_3_r_*SPP(16) + OP_l_3_c_3_r_*SPP(11));
  105. nextP(5,7) = OP_l_5_c_7_r_ - OP_l_1_c_7_r_*SPP(15) + OP_l_2_c_7_r_*SPP(16) + OP_l_3_c_7_r_*SPP(11);
  106. nextP(5,8) = OP_l_5_c_8_r_ - OP_l_1_c_8_r_*SPP(15) + OP_l_2_c_8_r_*SPP(16) + OP_l_3_c_8_r_*SPP(11);
  107. nextP(5,9) = OP_l_5_c_9_r_ - OP_l_1_c_9_r_*SPP(15) + OP_l_2_c_9_r_*SPP(16) + OP_l_3_c_9_r_*SPP(11);
  108. nextP(6,1) = SPP(5)*(OP_l_6_c_1_r_ + OP_l_1_c_1_r_*SPP(10) - OP_l_2_c_1_r_*SPP(13) + OP_l_3_c_1_r_*SPP(14)) + SPP(6)*(OP_l_6_c_2_r_ + OP_l_1_c_2_r_*SPP(10) - OP_l_2_c_2_r_*SPP(13) + OP_l_3_c_2_r_*SPP(14)) - SPP(9)*(OP_l_6_c_3_r_ + OP_l_1_c_3_r_*SPP(10) - OP_l_2_c_3_r_*SPP(13) + OP_l_3_c_3_r_*SPP(14)) + SPP(19)*(OP_l_6_c_7_r_ + OP_l_1_c_7_r_*SPP(10) - OP_l_2_c_7_r_*SPP(13) + OP_l_3_c_7_r_*SPP(14));
  109. nextP(6,2) = SPP(4)*(OP_l_6_c_2_r_ + OP_l_1_c_2_r_*SPP(10) - OP_l_2_c_2_r_*SPP(13) + OP_l_3_c_2_r_*SPP(14)) - SPP(3)*(OP_l_6_c_1_r_ + OP_l_1_c_1_r_*SPP(10) - OP_l_2_c_1_r_*SPP(13) + OP_l_3_c_1_r_*SPP(14)) + SPP(8)*(OP_l_6_c_3_r_ + OP_l_1_c_3_r_*SPP(10) - OP_l_2_c_3_r_*SPP(13) + OP_l_3_c_3_r_*SPP(14)) + SPP(19)*(OP_l_6_c_8_r_ + OP_l_1_c_8_r_*SPP(10) - OP_l_2_c_8_r_*SPP(13) + OP_l_3_c_8_r_*SPP(14));
  110. nextP(6,3) = SPP(1)*(OP_l_6_c_1_r_ + OP_l_1_c_1_r_*SPP(10) - OP_l_2_c_1_r_*SPP(13) + OP_l_3_c_1_r_*SPP(14)) - SPP(2)*(OP_l_6_c_2_r_ + OP_l_1_c_2_r_*SPP(10) - OP_l_2_c_2_r_*SPP(13) + OP_l_3_c_2_r_*SPP(14)) + SPP(7)*(OP_l_6_c_3_r_ + OP_l_1_c_3_r_*SPP(10) - OP_l_2_c_3_r_*SPP(13) + OP_l_3_c_3_r_*SPP(14)) + SPP(19)*(OP_l_6_c_9_r_ + OP_l_1_c_9_r_*SPP(10) - OP_l_2_c_9_r_*SPP(13) + OP_l_3_c_9_r_*SPP(14));
  111. nextP(6,4) = OP_l_6_c_4_r_ + SQ(2) + OP_l_1_c_4_r_*SPP(10) - OP_l_2_c_4_r_*SPP(13) + OP_l_3_c_4_r_*SPP(14) - SPP(12)*(OP_l_6_c_2_r_ + OP_l_1_c_2_r_*SPP(10) - OP_l_2_c_2_r_*SPP(13) + OP_l_3_c_2_r_*SPP(14)) + SPP(17)*(OP_l_6_c_1_r_ + OP_l_1_c_1_r_*SPP(10) - OP_l_2_c_1_r_*SPP(13) + OP_l_3_c_1_r_*SPP(14)) - SPP(18)*(OP_l_6_c_3_r_ + OP_l_1_c_3_r_*SPP(10) - OP_l_2_c_3_r_*SPP(13) + OP_l_3_c_3_r_*SPP(14));
  112. nextP(6,5) = OP_l_6_c_5_r_ + SQ(1) + OP_l_1_c_5_r_*SPP(10) - OP_l_2_c_5_r_*SPP(13) + OP_l_3_c_5_r_*SPP(14) - SPP(15)*(OP_l_6_c_1_r_ + OP_l_1_c_1_r_*SPP(10) - OP_l_2_c_1_r_*SPP(13) + OP_l_3_c_1_r_*SPP(14)) + SPP(11)*(OP_l_6_c_3_r_ + OP_l_1_c_3_r_*SPP(10) - OP_l_2_c_3_r_*SPP(13) + OP_l_3_c_3_r_*SPP(14)) + SPP(16)*(OP_l_6_c_2_r_ + OP_l_1_c_2_r_*SPP(10) - OP_l_2_c_2_r_*SPP(13) + OP_l_3_c_2_r_*SPP(14));
  113. nextP(6,6) = OP_l_6_c_6_r_ + OP_l_1_c_6_r_*SPP(10) - OP_l_2_c_6_r_*SPP(13) + OP_l_3_c_6_r_*SPP(14) + dvxNoise*(2*q0*q2 - 2*q1*q3)^2 + dvyNoise*(2*q0*q1 + 2*q2*q3)^2 + SPP(10)*(OP_l_6_c_1_r_ + OP_l_1_c_1_r_*SPP(10) - OP_l_2_c_1_r_*SPP(13) + OP_l_3_c_1_r_*SPP(14)) - SPP(13)*(OP_l_6_c_2_r_ + OP_l_1_c_2_r_*SPP(10) - OP_l_2_c_2_r_*SPP(13) + OP_l_3_c_2_r_*SPP(14)) + SPP(14)*(OP_l_6_c_3_r_ + OP_l_1_c_3_r_*SPP(10) - OP_l_2_c_3_r_*SPP(13) + OP_l_3_c_3_r_*SPP(14)) + dvzNoise*(SQ(5) - SQ(6) - SQ(7) + SQ(8))^2;
  114. nextP(6,7) = OP_l_6_c_7_r_ + OP_l_1_c_7_r_*SPP(10) - OP_l_2_c_7_r_*SPP(13) + OP_l_3_c_7_r_*SPP(14);
  115. nextP(6,8) = OP_l_6_c_8_r_ + OP_l_1_c_8_r_*SPP(10) - OP_l_2_c_8_r_*SPP(13) + OP_l_3_c_8_r_*SPP(14);
  116. nextP(6,9) = OP_l_6_c_9_r_ + OP_l_1_c_9_r_*SPP(10) - OP_l_2_c_9_r_*SPP(13) + OP_l_3_c_9_r_*SPP(14);
  117. nextP(7,1) = OP_l_7_c_1_r_*SPP(5) + OP_l_7_c_2_r_*SPP(6) - OP_l_7_c_3_r_*SPP(9) + OP_l_7_c_7_r_*SPP(19);
  118. nextP(7,2) = OP_l_7_c_2_r_*SPP(4) - OP_l_7_c_1_r_*SPP(3) + OP_l_7_c_3_r_*SPP(8) + OP_l_7_c_8_r_*SPP(19);
  119. nextP(7,3) = OP_l_7_c_1_r_*SPP(1) - OP_l_7_c_2_r_*SPP(2) + OP_l_7_c_3_r_*SPP(7) + OP_l_7_c_9_r_*SPP(19);
  120. nextP(7,4) = OP_l_7_c_4_r_ - OP_l_7_c_2_r_*SPP(12) + OP_l_7_c_1_r_*SPP(17) - OP_l_7_c_3_r_*SPP(18);
  121. nextP(7,5) = OP_l_7_c_5_r_ + OP_l_7_c_3_r_*SPP(11) - OP_l_7_c_1_r_*SPP(15) + OP_l_7_c_2_r_*SPP(16);
  122. nextP(7,6) = OP_l_7_c_6_r_ + OP_l_7_c_1_r_*SPP(10) - OP_l_7_c_2_r_*SPP(13) + OP_l_7_c_3_r_*SPP(14);
  123. nextP(7,7) = OP_l_7_c_7_r_;
  124. nextP(7,8) = OP_l_7_c_8_r_;
  125. nextP(7,9) = OP_l_7_c_9_r_;
  126. nextP(8,1) = OP_l_8_c_1_r_*SPP(5) + OP_l_8_c_2_r_*SPP(6) - OP_l_8_c_3_r_*SPP(9) + OP_l_8_c_7_r_*SPP(19);
  127. nextP(8,2) = OP_l_8_c_2_r_*SPP(4) - OP_l_8_c_1_r_*SPP(3) + OP_l_8_c_3_r_*SPP(8) + OP_l_8_c_8_r_*SPP(19);
  128. nextP(8,3) = OP_l_8_c_1_r_*SPP(1) - OP_l_8_c_2_r_*SPP(2) + OP_l_8_c_3_r_*SPP(7) + OP_l_8_c_9_r_*SPP(19);
  129. nextP(8,4) = OP_l_8_c_4_r_ - OP_l_8_c_2_r_*SPP(12) + OP_l_8_c_1_r_*SPP(17) - OP_l_8_c_3_r_*SPP(18);
  130. nextP(8,5) = OP_l_8_c_5_r_ + OP_l_8_c_3_r_*SPP(11) - OP_l_8_c_1_r_*SPP(15) + OP_l_8_c_2_r_*SPP(16);
  131. nextP(8,6) = OP_l_8_c_6_r_ + OP_l_8_c_1_r_*SPP(10) - OP_l_8_c_2_r_*SPP(13) + OP_l_8_c_3_r_*SPP(14);
  132. nextP(8,7) = OP_l_8_c_7_r_;
  133. nextP(8,8) = OP_l_8_c_8_r_;
  134. nextP(8,9) = OP_l_8_c_9_r_;
  135. nextP(9,1) = OP_l_9_c_1_r_*SPP(5) + OP_l_9_c_2_r_*SPP(6) - OP_l_9_c_3_r_*SPP(9) + OP_l_9_c_7_r_*SPP(19);
  136. nextP(9,2) = OP_l_9_c_2_r_*SPP(4) - OP_l_9_c_1_r_*SPP(3) + OP_l_9_c_3_r_*SPP(8) + OP_l_9_c_8_r_*SPP(19);
  137. nextP(9,3) = OP_l_9_c_1_r_*SPP(1) - OP_l_9_c_2_r_*SPP(2) + OP_l_9_c_3_r_*SPP(7) + OP_l_9_c_9_r_*SPP(19);
  138. nextP(9,4) = OP_l_9_c_4_r_ - OP_l_9_c_2_r_*SPP(12) + OP_l_9_c_1_r_*SPP(17) - OP_l_9_c_3_r_*SPP(18);
  139. nextP(9,5) = OP_l_9_c_5_r_ + OP_l_9_c_3_r_*SPP(11) - OP_l_9_c_1_r_*SPP(15) + OP_l_9_c_2_r_*SPP(16);
  140. nextP(9,6) = OP_l_9_c_6_r_ + OP_l_9_c_1_r_*SPP(10) - OP_l_9_c_2_r_*SPP(13) + OP_l_9_c_3_r_*SPP(14);
  141. nextP(9,7) = OP_l_9_c_7_r_;
  142. nextP(9,8) = OP_l_9_c_8_r_;
  143. nextP(9,9) = OP_l_9_c_9_r_;