forked from Archive/PX4-Autopilot
Roll pitch yaw should be verified again
This commit is contained in:
parent
32bace0824
commit
f547044203
|
@ -139,48 +139,48 @@ void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float
|
||||||
// Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
|
// Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
|
||||||
if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
|
if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
|
||||||
|
|
||||||
// Normalise accelerometer measurement
|
// Normalise accelerometer measurement
|
||||||
recipNorm = invSqrt(ax * ax + ay * ay + az * az);
|
recipNorm = invSqrt(ax * ax + ay * ay + az * az);
|
||||||
ax *= recipNorm;
|
ax *= recipNorm;
|
||||||
ay *= recipNorm;
|
ay *= recipNorm;
|
||||||
az *= recipNorm;
|
az *= recipNorm;
|
||||||
|
|
||||||
// Estimated direction of gravity and vector perpendicular to magnetic flux
|
// Estimated direction of gravity and vector perpendicular to magnetic flux
|
||||||
halfvx = q1 * q3 - q0 * q2;
|
halfvx = q1 * q3 - q0 * q2;
|
||||||
halfvy = q0 * q1 + q2 * q3;
|
halfvy = q0 * q1 + q2 * q3;
|
||||||
halfvz = q0 * q0 - 0.5f + q3 * q3;
|
halfvz = q0 * q0 - 0.5f + q3 * q3;
|
||||||
|
|
||||||
// Error is sum of cross product between estimated and measured direction of gravity
|
// Error is sum of cross product between estimated and measured direction of gravity
|
||||||
halfex = (ay * halfvz - az * halfvy);
|
halfex = (ay * halfvz - az * halfvy);
|
||||||
halfey = (az * halfvx - ax * halfvz);
|
halfey = (az * halfvx - ax * halfvz);
|
||||||
halfez = (ax * halfvy - ay * halfvx);
|
halfez = (ax * halfvy - ay * halfvx);
|
||||||
|
|
||||||
// Compute and apply integral feedback if enabled
|
// Compute and apply integral feedback if enabled
|
||||||
if(twoKi > 0.0f) {
|
if(twoKi > 0.0f) {
|
||||||
integralFBx += twoKi * halfex * dt; // integral error scaled by Ki
|
integralFBx += twoKi * halfex * dt; // integral error scaled by Ki
|
||||||
integralFBy += twoKi * halfey * dt;
|
integralFBy += twoKi * halfey * dt;
|
||||||
integralFBz += twoKi * halfez * dt;
|
integralFBz += twoKi * halfez * dt;
|
||||||
gx += integralFBx; // apply integral feedback
|
gx += integralFBx; // apply integral feedback
|
||||||
gy += integralFBy;
|
gy += integralFBy;
|
||||||
gz += integralFBz;
|
gz += integralFBz;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
integralFBx = 0.0f; // prevent integral windup
|
integralFBx = 0.0f; // prevent integral windup
|
||||||
integralFBy = 0.0f;
|
integralFBy = 0.0f;
|
||||||
integralFBz = 0.0f;
|
integralFBz = 0.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Apply proportional feedback
|
// Apply proportional feedback
|
||||||
gx += twoKp * halfex;
|
gx += twoKp * halfex;
|
||||||
gy += twoKp * halfey;
|
gy += twoKp * halfey;
|
||||||
gz += twoKp * halfez;
|
gz += twoKp * halfez;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Integrate rate of change of quaternion
|
// Integrate rate of change of quaternion
|
||||||
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);
|
||||||
|
@ -209,17 +209,17 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az
|
||||||
// Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
|
// Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
|
||||||
if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
|
if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
|
||||||
|
|
||||||
// Normalise accelerometer measurement
|
// Normalise accelerometer measurement
|
||||||
recipNorm = invSqrt(ax * ax + ay * ay + az * az);
|
recipNorm = invSqrt(ax * ax + ay * ay + az * az);
|
||||||
ax *= recipNorm;
|
ax *= recipNorm;
|
||||||
ay *= recipNorm;
|
ay *= recipNorm;
|
||||||
az *= recipNorm;
|
az *= recipNorm;
|
||||||
|
|
||||||
// Normalise magnetometer measurement
|
// Normalise magnetometer measurement
|
||||||
recipNorm = invSqrt(mx * mx + my * my + mz * mz);
|
recipNorm = invSqrt(mx * mx + my * my + mz * mz);
|
||||||
mx *= recipNorm;
|
mx *= recipNorm;
|
||||||
my *= recipNorm;
|
my *= recipNorm;
|
||||||
mz *= recipNorm;
|
mz *= recipNorm;
|
||||||
|
|
||||||
// Auxiliary variables to avoid repeated arithmetic
|
// Auxiliary variables to avoid repeated arithmetic
|
||||||
q0q0 = q0 * q0;
|
q0q0 = q0 * q0;
|
||||||
|
@ -239,45 +239,45 @@ void MahonyAHRSupdate(float gx, float gy, float gz, float ax, float ay, float az
|
||||||
bx = sqrt(hx * hx + hy * hy);
|
bx = sqrt(hx * hx + hy * hy);
|
||||||
bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2));
|
bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2));
|
||||||
|
|
||||||
// Estimated direction of gravity and magnetic field
|
// Estimated direction of gravity and magnetic field
|
||||||
halfvx = q1q3 - q0q2;
|
halfvx = q1q3 - q0q2;
|
||||||
halfvy = q0q1 + q2q3;
|
halfvy = q0q1 + q2q3;
|
||||||
halfvz = q0q0 - 0.5f + q3q3;
|
halfvz = q0q0 - 0.5f + q3q3;
|
||||||
halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2);
|
halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2);
|
||||||
halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3);
|
halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3);
|
||||||
halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2);
|
halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2);
|
||||||
|
|
||||||
// Error is sum of cross product between estimated direction and measured direction of field vectors
|
// Error is sum of cross product between estimated direction and measured direction of field vectors
|
||||||
halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy);
|
halfex = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy);
|
||||||
halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz);
|
halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz);
|
||||||
halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx);
|
halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx);
|
||||||
|
|
||||||
// Compute and apply integral feedback if enabled
|
// Compute and apply integral feedback if enabled
|
||||||
if(twoKi > 0.0f) {
|
if(twoKi > 0.0f) {
|
||||||
integralFBx += twoKi * halfex * dt; // integral error scaled by Ki
|
integralFBx += twoKi * halfex * dt; // integral error scaled by Ki
|
||||||
integralFBy += twoKi * halfey * dt;
|
integralFBy += twoKi * halfey * dt;
|
||||||
integralFBz += twoKi * halfez * dt;
|
integralFBz += twoKi * halfez * dt;
|
||||||
gx += integralFBx; // apply integral feedback
|
gx += integralFBx; // apply integral feedback
|
||||||
gy += integralFBy;
|
gy += integralFBy;
|
||||||
gz += integralFBz;
|
gz += integralFBz;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
integralFBx = 0.0f; // prevent integral windup
|
integralFBx = 0.0f; // prevent integral windup
|
||||||
integralFBy = 0.0f;
|
integralFBy = 0.0f;
|
||||||
integralFBz = 0.0f;
|
integralFBz = 0.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Apply proportional feedback
|
// Apply proportional feedback
|
||||||
gx += twoKp * halfex;
|
gx += twoKp * halfex;
|
||||||
gy += twoKp * halfey;
|
gy += twoKp * halfey;
|
||||||
gz += twoKp * halfez;
|
gz += twoKp * halfez;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Integrate rate of change of quaternion
|
// Integrate rate of change of quaternion
|
||||||
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