calcQ.m 1.4 KB

12345678910111213141516171819202122232425262728293031323334
  1. function Q = calcQ(daxNoise,dayNoise,dazNoise,dvxNoise,dvyNoise,dvzNoise,q0,q1,q2,q3)
  2. %CALCQ
  3. % Q = CALCQ(DAXNOISE,DAYNOISE,DAZNOISE,DVXNOISE,DVYNOISE,DVZNOISE,Q0,Q1,Q2,Q3)
  4. % This function was generated by the Symbolic Math Toolbox version 5.8.
  5. % 27-Dec-2014 13:59:04
  6. t3 = q0.^2;
  7. t4 = q1.^2;
  8. t5 = q2.^2;
  9. t6 = q3.^2;
  10. t2 = t3+t4+t5+t6;
  11. t7 = t2.^2;
  12. t11 = q0.*q3.*2.0;
  13. t12 = q1.*q2.*2.0;
  14. t8 = t11-t12;
  15. t13 = q0.*q2.*2.0;
  16. t14 = q1.*q3.*2.0;
  17. t9 = t13+t14;
  18. t10 = t3+t4-t5-t6;
  19. t15 = q0.*q1.*2.0;
  20. t16 = t11+t12;
  21. t17 = dvxNoise.*t10.*t16;
  22. t18 = t3-t4+t5-t6;
  23. t19 = q2.*q3.*2.0;
  24. t20 = t15-t19;
  25. t21 = t15+t19;
  26. t22 = t3-t4-t5+t6;
  27. t23 = t13-t14;
  28. t24 = dvzNoise.*t9.*t22;
  29. t25 = t24-dvxNoise.*t10.*t23-dvyNoise.*t8.*t21;
  30. t26 = dvyNoise.*t18.*t21;
  31. t27 = t26-dvxNoise.*t16.*t23-dvzNoise.*t20.*t22;
  32. Q = reshape([daxNoise.*t7,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,dayNoise.*t7,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,dazNoise.*t7,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,dvxNoise.*t10.^2+dvyNoise.*t8.^2+dvzNoise.*t9.^2,t17-dvyNoise.*t8.*t18-dvzNoise.*t9.*t20,t25,0.0,0.0,0.0,0.0,0.0,0.0,t17-dvzNoise.*t9.*(t15-q2.*q3.*2.0)-dvyNoise.*t8.*t18,dvxNoise.*t16.^2+dvyNoise.*t18.^2+dvzNoise.*t20.^2,t27,0.0,0.0,0.0,0.0,0.0,0.0,t25,t27,dvxNoise.*t23.^2+dvyNoise.*t21.^2+dvzNoise.*t22.^2,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0],[9, 9]);