1 | // %flair:license{
|
---|
2 | // This file is part of the Flair framework distributed under the
|
---|
3 | // CECILL-C License, Version 1.0.
|
---|
4 | // %flair:license}
|
---|
5 |
|
---|
6 | // created: 2014/04/28
|
---|
7 | // filename: AhrsComplementaryFilter.cpp
|
---|
8 | //
|
---|
9 | // authors: Augustin Manecy (RT-MaG Toolbox author, augustin.manecy@gmail.com)
|
---|
10 | // API changes by Guillaume Sanahuja to fit the Flair framework
|
---|
11 | //
|
---|
12 | // version: $Id: $
|
---|
13 | //
|
---|
14 | // purpose: Class defining an Ahrs complementary filter
|
---|
15 | //
|
---|
16 | //
|
---|
17 | /*********************************************************************/
|
---|
18 |
|
---|
19 | #include "AhrsComplementaryFilter.h"
|
---|
20 | #include <Imu.h>
|
---|
21 | #include <DoubleSpinBox.h>
|
---|
22 | #include <GridLayout.h>
|
---|
23 | #include <ImuData.h>
|
---|
24 | #include <AhrsData.h>
|
---|
25 | #include <math.h>
|
---|
26 |
|
---|
27 | #define G 9.81
|
---|
28 |
|
---|
29 | using std::string;
|
---|
30 | using namespace flair::core;
|
---|
31 | using namespace flair::gui;
|
---|
32 | using namespace flair::sensor;
|
---|
33 |
|
---|
34 | namespace flair { namespace filter {
|
---|
35 |
|
---|
36 | AhrsComplementaryFilter::AhrsComplementaryFilter(const Imu* parent,string name): isInit(false), Ahrs(parent,name) {
|
---|
37 |
|
---|
38 | QHat.q0=1;
|
---|
39 | QHat.q1=0;
|
---|
40 | QHat.q2=0;
|
---|
41 | QHat.q3=0;
|
---|
42 | BHat.x=0;
|
---|
43 | BHat.y=0;
|
---|
44 | BHat.z=0;
|
---|
45 |
|
---|
46 | ka[0]=new DoubleSpinBox(parent->GetLayout()->NewRow(),"ka[0]:",0.,10,0.1,2,0.5);
|
---|
47 | ka[1]=new DoubleSpinBox(parent->GetLayout()->LastRowLastCol(),"ka[1]:",0.,10,0.1,2,0.5);
|
---|
48 | ka[2]=new DoubleSpinBox(parent->GetLayout()->LastRowLastCol(),"ka[2]:",0.,10.,0.1,2,0.);
|
---|
49 |
|
---|
50 | kb[0]=new DoubleSpinBox(parent->GetLayout()->NewRow(),"kb[0]:",0.,10,0.1,2,0.01);
|
---|
51 | kb[1]=new DoubleSpinBox(parent->GetLayout()->LastRowLastCol(),"kb[1]:",0.,10,0.1,2,0.01);
|
---|
52 | kb[2]=new DoubleSpinBox(parent->GetLayout()->LastRowLastCol(),"kb[2]:",0.,10,0.1,2,0.01);
|
---|
53 |
|
---|
54 | }
|
---|
55 |
|
---|
56 | AhrsComplementaryFilter::~AhrsComplementaryFilter() {
|
---|
57 |
|
---|
58 | }
|
---|
59 |
|
---|
60 | void AhrsComplementaryFilter::UpdateFrom(const io_data *data) {
|
---|
61 | ImuData *input=(ImuData*)data;
|
---|
62 | float delta_t;
|
---|
63 | AhrsData* ahrsData;
|
---|
64 | GetDatas(&ahrsData);
|
---|
65 | Vector3D rawAcc,rawMag,rawGyr;
|
---|
66 | input->GetRawAccMagAndGyr(rawAcc,rawMag,rawGyr);
|
---|
67 |
|
---|
68 | delta_t=(float)(data->DataTime()-previous_time)/1000000000.;
|
---|
69 | previous_time=data->DataTime();
|
---|
70 |
|
---|
71 | Vector3D aBar,aHat,aTilde;
|
---|
72 | Vector3D mBar,mHat,mTilde;
|
---|
73 | Vector3D alpha,dBHat,omegaHat;
|
---|
74 | Quaternion dQHat;
|
---|
75 |
|
---|
76 | //float ka[3]={0.5,0.5,0};
|
---|
77 | //float kb[3]={0.01,0.01,0.01};
|
---|
78 | float k_m[3]= {0,0,0};
|
---|
79 |
|
---|
80 | if(isInit==true) {
|
---|
81 | // CORRECTION FORM ACCELEROMETER
|
---|
82 | aBar = rawAcc;
|
---|
83 |
|
---|
84 | // estimation of IMU vector using QHat (estimated quaternion): aHat = Inv(QHat) * g
|
---|
85 | /*
|
---|
86 | Inv(QHat) = [q0 -q1 -q2 -q3]'
|
---|
87 | Inv(QHat)*g = [1-2(q2^2+q3^2) 2(q1q2+q0q3) 2(q1q3-q0q2)] [0]
|
---|
88 | [ 2(q1q2-q0q3) 1-2(q1^2+q3^2)) 2(q2q3+q0q1)] * [0]
|
---|
89 | [ 2(q1q3+q0q2) 2(q2q3-q0q1) 1-2(q1^2+q2^2)] [g]
|
---|
90 | */
|
---|
91 | aHat.x = -2*G*(QHat.q1*QHat.q3 - QHat.q0*QHat.q2);
|
---|
92 | aHat.y = -2*G*(QHat.q2*QHat.q3 + QHat.q0*QHat.q1);
|
---|
93 | aHat.z = -G*(1-2.0*(QHat.q1*QHat.q1 + QHat.q2*QHat.q2));
|
---|
94 |
|
---|
95 | // cross(aHat, aBar)
|
---|
96 | aTilde=CrossProduct(aHat, aBar);
|
---|
97 |
|
---|
98 | // CORRECTION FROM FICTIOUS MAGNETOMETER (to avoid drift of yaw)
|
---|
99 | // estimation of IMU vector using QHat (estimated quaternion): mHat = Inv(QHat) * m_ref = Inv(QHat) * [1.0, 0.0, 0.0]'
|
---|
100 | /*
|
---|
101 | Inv(QHat) = [q0 -q1 -q2 -q3]'
|
---|
102 | Inv(QHat)*g = [1-2(q2^2+q3^2) 2(q1q2+q0q3) 2(q1q3-q0q2)] [1]
|
---|
103 | [ 2(q1q2-q0q3) 1-2(q1^2+q3^2)) 2(q2q3+q0q1)] * [0]
|
---|
104 | [ 2(q1q3+q0q2) 2(q2q3-q0q1) 1-2(q1^2+q2^2)] [0]
|
---|
105 | */
|
---|
106 | mBar.x=1;
|
---|
107 | mBar.y=0;
|
---|
108 | mBar.z=0;
|
---|
109 |
|
---|
110 | mHat.x = (1-2.0*(QHat.q2*QHat.q2 + QHat.q3*QHat.q3));
|
---|
111 | mHat.y = 2.0*(QHat.q1*QHat.q2 - QHat.q0*QHat.q3);
|
---|
112 | mHat.z = 2.0*(QHat.q1*QHat.q3 + QHat.q0*QHat.q2);
|
---|
113 |
|
---|
114 | // compute the error between mHat and mTilde
|
---|
115 | mTilde=CrossProduct(mHat, mBar);
|
---|
116 |
|
---|
117 | // Compute the debiased rotation speed
|
---|
118 | omegaHat = rawGyr - BHat;
|
---|
119 |
|
---|
120 | // calculate the correction to apply to the quaternion
|
---|
121 | alpha.x = (ka[0]->Value()*aTilde.x)/(G*G) + (k_m[0]*mTilde.x);
|
---|
122 | alpha.y = (ka[1]->Value()*aTilde.y)/(G*G) + (k_m[1]*mTilde.y);
|
---|
123 | alpha.z = (ka[2]->Value()*aTilde.z)/(G*G) + (k_m[2]*mTilde.z);
|
---|
124 |
|
---|
125 | // Bias derivative
|
---|
126 | dBHat.x = kb[0]->Value() * alpha.x;
|
---|
127 | dBHat.y = kb[1]->Value() * alpha.y;
|
---|
128 | dBHat.z = kb[2]->Value() * alpha.z;
|
---|
129 |
|
---|
130 | // Bias integration
|
---|
131 | BHat = BHat+dBHat*delta_t;
|
---|
132 |
|
---|
133 | // Quaternion derivative: dQHat = 0.5*(QHat*Q_corr)
|
---|
134 | // Q_corr: Corrected pure rotation quaternion for integration
|
---|
135 | dQHat=QHat.GetDerivative(omegaHat - alpha);
|
---|
136 |
|
---|
137 | // Quaternion integration
|
---|
138 | QHat = QHat +dQHat*delta_t; // delta_t: sampling period [s]
|
---|
139 |
|
---|
140 | QHat.Normalize();
|
---|
141 |
|
---|
142 | ahrsData->SetQuaternionAndAngularRates(QHat,rawGyr - BHat);
|
---|
143 |
|
---|
144 | } else {
|
---|
145 | isInit=true;
|
---|
146 | }
|
---|
147 |
|
---|
148 | ahrsData->SetDataTime(data->DataTime());
|
---|
149 | ProcessUpdate(ahrsData);
|
---|
150 | }
|
---|
151 |
|
---|
152 | } // end namespace filter
|
---|
153 | } // end namespace flair
|
---|