forked from Archive/PX4-Autopilot
Roll pitch yaw should be verified again
This commit is contained in:
parent
32bace0824
commit
f547044203
|
@ -180,7 +180,7 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float
|
||||||
gx *= (0.5f * dt); // pre-multiply common factors
|
gx *= (0.5f * dt); // pre-multiply common factors
|
||||||
gy *= (0.5f * dt);
|
gy *= (0.5f * dt);
|
||||||
gz *= (0.5f * dt);
|
gz *= (0.5f * dt);
|
||||||
q0 += (-q1 * gx - q2 * gy - q3 * gz);
|
q0 +=(-q1 * gx - q2 * gy - q3 * gz);
|
||||||
q1 += (q0 * gx + q2 * gz - q3 * gy);
|
q1 += (q0 * gx + q2 * gz - q3 * gy);
|
||||||
q2 += (q0 * gy - q1 * gz + q3 * gx);
|
q2 += (q0 * gy - q1 * gz + q3 * gx);
|
||||||
q3 += (q0 * gz + q1 * gy - q2 * gx);
|
q3 += (q0 * gz + q1 * gy - q2 * gx);
|
||||||
|
@ -277,7 +277,7 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az
|
||||||
gx *= (0.5f * dt); // pre-multiply common factors
|
gx *= (0.5f * dt); // pre-multiply common factors
|
||||||
gy *= (0.5f * dt);
|
gy *= (0.5f * dt);
|
||||||
gz *= (0.5f * dt);
|
gz *= (0.5f * dt);
|
||||||
q0 += (-q1 * gx - q2 * gy - q3 * gz);
|
q0 +=(-q1 * gx - q2 * gy - q3 * gz);
|
||||||
q1 += (q0 * gx + q2 * gz - q3 * gy);
|
q1 += (q0 * gx + q2 * gz - q3 * gy);
|
||||||
q2 += (q0 * gy - q1 * gz + q3 * gx);
|
q2 += (q0 * gy - q1 * gz + q3 * gx);
|
||||||
q3 += (q0 * gz + q1 * gy - q2 * gx);
|
q3 += (q0 * gz + q1 * gy - q2 * gx);
|
||||||
|
@ -515,24 +515,28 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||||
|
|
||||||
MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],acc[0],acc[1],acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt);
|
MahonyAHRSupdate(gyro[0],gyro[1],gyro[2],acc[0],acc[1],acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt);
|
||||||
|
|
||||||
float aSq = q0*q0;
|
float aSq = q0*q0; // 1
|
||||||
float bSq = q1*q1;
|
float bSq = q1*q1; // 2
|
||||||
float cSq = q2*q2;
|
float cSq = q2*q2; // 3
|
||||||
float dSq = q3*q3;
|
float dSq = q3*q3; // 4
|
||||||
float a = q0;
|
float a = q0;
|
||||||
float b = q1;
|
float b = q1;
|
||||||
float c = q2;
|
float c = q2;
|
||||||
float d = q3;
|
float d = q3;
|
||||||
|
|
||||||
Rot_matrix[0] = aSq + bSq - cSq - dSq; // 11
|
Rot_matrix[0] = 2*aSq - 1 + 2*bSq; // 11
|
||||||
Rot_matrix[1] = 2.0 * (b * c - a * d); // 12
|
//Rot_matrix[1] = 2.0 * (b * c - a * d); // 12
|
||||||
Rot_matrix[2] = 2.0 * (a * c + b * d); // 13
|
//Rot_matrix[2] = 2.0 * (a * c + b * d); // 13
|
||||||
Rot_matrix[3] = 2.0 * (b * c + a * d); // 21
|
Rot_matrix[3] = 2.0 * (b * c - a * d); // 21
|
||||||
Rot_matrix[4] = aSq - bSq + cSq - dSq; // 22
|
//Rot_matrix[4] = aSq - bSq + cSq - dSq; // 22
|
||||||
Rot_matrix[5] = 2.0 * (c * d - a * b); // 23
|
//Rot_matrix[5] = 2.0 * (c * d - a * b); // 23
|
||||||
Rot_matrix[6] = 2.0 * (b * d - a * c); // 31
|
Rot_matrix[6] = 2.0 * (b * d + a * c); // 31
|
||||||
Rot_matrix[7] = 2.0 * (a * b + c * d); // 32
|
Rot_matrix[7] = 2.0 * (c * d - a * b); // 32
|
||||||
Rot_matrix[8] = aSq - bSq - cSq + dSq; // 33
|
Rot_matrix[8] = 2*aSq - 1 + 2*dSq; // 33
|
||||||
|
|
||||||
|
//euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]);
|
||||||
|
//euler[1] = asinf(-Rot_matrix[6]);
|
||||||
|
//euler[2] = atan2f(Rot_matrix[3],Rot_matrix[0]);
|
||||||
|
|
||||||
/* FIXME : Work around this later...
|
/* FIXME : Work around this later...
|
||||||
float theta = asinf(-Rot_matrix[6]); // -r_{31}
|
float theta = asinf(-Rot_matrix[6]); // -r_{31}
|
||||||
|
@ -550,13 +554,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||||
}
|
}
|
||||||
*/
|
*/
|
||||||
|
|
||||||
float q1q1 = q1*q1;
|
euler[0] = atan2f(2*(q0*q1+q2*q3),1-2*(q1*q1+q2*q2));
|
||||||
float q2q2 = q2*q2;
|
euler[1] = asinf(2*(q0*q2-q3*q1));
|
||||||
float q3q3 = q3*q3;
|
euler[2] = atan2f(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3));
|
||||||
|
|
||||||
euler[0] = atan2f(2*(q0*q1 + q2*q3),1-2*(q1q1+q2q2)); // roll
|
|
||||||
euler[1] = asinf(2*(q0*q2 - q3*q1)); // pitch
|
|
||||||
euler[2] = atan2f(2*(q0*q3 + q1*q2),1-2*(q2q2 + q3q3)); // yaw
|
|
||||||
|
|
||||||
|
|
||||||
/* swap values for next iteration, check for fatal inputs */
|
/* swap values for next iteration, check for fatal inputs */
|
||||||
|
|
|
@ -7,7 +7,7 @@
|
||||||
#include "attitude_estimator_so3_comp_params.h"
|
#include "attitude_estimator_so3_comp_params.h"
|
||||||
|
|
||||||
/* This is filter gain for nonlinear SO3 complementary filter */
|
/* This is filter gain for nonlinear SO3 complementary filter */
|
||||||
PARAM_DEFINE_FLOAT(SO3_COMP_KP, 1.0f);
|
PARAM_DEFINE_FLOAT(SO3_COMP_KP, 0.5f);
|
||||||
PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.0f);
|
PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.0f);
|
||||||
|
|
||||||
/* offsets in roll, pitch and yaw of sensor plane and body */
|
/* offsets in roll, pitch and yaw of sensor plane and body */
|
||||||
|
|
Loading…
Reference in New Issue