APM:Libraries
SoloGimbalEKF.h
Go to the documentation of this file.
1 /*
2  smaller EKF for simpler estimation applications
3 
4  Converted from Matlab to C++ by Paul Riseborough
5 
6  This program is free software: you can redistribute it and/or modify
7  it under the terms of the GNU General Public License as published by
8  the Free Software Foundation, either version 3 of the License, or
9  (at your option) any later version.
10 
11  This program is distributed in the hope that it will be useful,
12  but WITHOUT ANY WARRANTY; without even the implied warranty of
13  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  GNU General Public License for more details.
15 
16  You should have received a copy of the GNU General Public License
17  along with this program. If not, see <http://www.gnu.org/licenses/>.
18  */
19 #pragma once
20 
21 #include <AP_Math/AP_Math.h>
23 #include <AP_Baro/AP_Baro.h>
25 #include <AP_Compass/AP_Compass.h>
26 #include <AP_Param/AP_Param.h>
28 #include <AP_AHRS/AP_AHRS.h>
29 //#include <AP_NavEKF2/AP_NavEKF2.h>
30 
31 #include <AP_Math/vectorN.h>
32 
34 {
35 public:
36  typedef float ftype;
37 #if MATH_CHECK_INDEXES
38  typedef VectorN<ftype,2> Vector2;
39  typedef VectorN<ftype,3> Vector3;
40  typedef VectorN<ftype,5> Vector5;
41  typedef VectorN<ftype,6> Vector6;
42  typedef VectorN<ftype,8> Vector8;
43  typedef VectorN<ftype,9> Vector9;
56 #else
57  typedef ftype Vector2[2];
58  typedef ftype Vector3[3];
59  typedef ftype Vector5[5];
60  typedef ftype Vector6[6];
61  typedef ftype Vector8[8];
62  typedef ftype Vector9[9];
63  typedef ftype Vector10[10];
64  typedef ftype Vector11[11];
65  typedef ftype Vector13[13];
66  typedef ftype Vector14[14];
67  typedef ftype Vector15[15];
68  typedef ftype Vector22[22];
69  typedef ftype Vector31[31];
70  typedef ftype Vector34[34];
71  typedef ftype Matrix3[3][3];
72  typedef ftype Matrix22[22][22];
73  typedef ftype Matrix34_50[34][50];
74  typedef uint32_t Vector_u32_50[50];
75 #endif
76 
77  // Constructor
79 
80  // Run the EKF main loop once every time we receive sensor data
81  void RunEKF(float delta_time, const Vector3f &delta_angles, const Vector3f &delta_velocity, const Vector3f &joint_angles);
82 
83  void reset();
84 
85  // get some debug information
86  void getDebug(float &tilt, Vector3f &velocity, Vector3f &euler, Vector3f &gyroBias) const;
87 
88  // get gyro bias data
89  void getGyroBias(Vector3f &gyroBias) const;
90 
91  // set gyro bias
92  void setGyroBias(const Vector3f &gyroBias);
93 
94  // get quaternion data
95  void getQuat(Quaternion &quat) const;
96 
97  // get filter alignment status - true is aligned
98  bool getStatus(void) const;
99 
100  static const struct AP_Param::GroupInfo var_info[];
101 
102 private:
104 
105  // the states are available in two forms, either as a Vector13 or
106  // broken down as individual elements. Both are equivalent (same
107  // memory)
108  Vector13 states;
109  struct state_elements {
110  Vector3f angErr; // 0..2 rotation vector representing the growth in angle error since the last state correction (rad)
111  Vector3f velocity; // 3..5 NED velocity (m/s)
112  Vector3f delAngBias; // 6..8 estimated bias errors in the IMU delta angles
113  Quaternion quat; // 9..12 these states are used by the INS prediction only and are not used by the EKF state equations.
114  } &state;
115 
116  // data from sensors
117  struct {
120  float gPhi;
121  float gPsi;
122  float gTheta;
123  } gSense;
124 
125  float Cov[9][9]; // covariance matrix
126  Matrix3f Tsn; // Sensor to NED rotation matrix
127  float TiltCorrection; // Angle correction applied to tilt from last velocity fusion (rad)
128  bool newDataMag; // true when new magnetometer data is waiting to be used
129  uint32_t StartTime_ms; // time the EKF was started (msec)
130  bool FiltInit; // true when EKF is initialised
131  bool YawAligned; // true when EKF heading is initialised
132  float cosPhi;// = cosf(gSense.gPhi);
133  float cosTheta;// = cosf(gSense.gTheta);
134  float sinPhi;// = sinf(gSense.gPhi);
135  float sinTheta;// = sinf(gSense.gTheta);
136  float sinPsi;// = sinf(gSense.gPsi);
137  float cosPsi;// = cosf(gSense.gPsi);
138  uint32_t lastMagUpdate;
140 
142  float dtIMU;
143 
144  // States used for unwrapping of compass yaw error
147 
148  // state prediction
149  void predictStates();
150 
151  // EKF covariance prediction
152  void predictCovariance();
153 
154  // EKF velocity fusion
155  void fuseVelocity();
156 
157  // read magnetometer data
158  void readMagData();
159 
160  // EKF compass fusion
161  void fuseCompass();
162 
163  // Perform an initial heading alignment using the magnetic field and assumed declination
164  void alignHeading();
165 
166  // Calculate magnetic heading innovation
167  float calcMagHeadingInnov();
168 
169  // Force symmmetry and non-negative diagonals on state covarinace matrix
170  void fixCovariance();
171 };
float TiltCorrection
ftype Vector31[31]
Definition: SoloGimbalEKF.h:69
ftype Vector6[6]
Definition: SoloGimbalEKF.h:60
ftype Vector34[34]
Definition: SoloGimbalEKF.h:70
uint32_t Vector_u32_50[50]
Definition: SoloGimbalEKF.h:74
uint32_t imuSampleTime_ms
bool getStatus(void) const
ftype Matrix3[3][3]
Definition: SoloGimbalEKF.h:71
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
void predictCovariance()
void getGyroBias(Vector3f &gyroBias) const
static const struct AP_Param::GroupInfo var_info[]
ftype Vector10[10]
Definition: SoloGimbalEKF.h:63
float Cov[9][9]
ftype Vector11[11]
Definition: SoloGimbalEKF.h:64
ftype Vector9[9]
Definition: SoloGimbalEKF.h:62
ftype Matrix34_50[34][50]
Definition: SoloGimbalEKF.h:73
struct SoloGimbalEKF::@137 gSense
ftype Vector13[13]
Definition: SoloGimbalEKF.h:65
Vector3f delVel
ftype Vector14[14]
Definition: SoloGimbalEKF.h:66
ftype Vector2[2]
Definition: SoloGimbalEKF.h:57
float innovationIncrement
SoloGimbalEKF(const AP_AHRS_NavEKF &ahrs)
ftype Vector8[8]
Definition: SoloGimbalEKF.h:61
void getDebug(float &tilt, Vector3f &velocity, Vector3f &euler, Vector3f &gyroBias) const
A system for managing and storing variables that are of general interest to the system.
void getQuat(Quaternion &quat) const
ftype Vector22[22]
Definition: SoloGimbalEKF.h:68
const AP_AHRS_NavEKF & _ahrs
void RunEKF(float delta_time, const Vector3f &delta_angles, const Vector3f &delta_velocity, const Vector3f &joint_angles)
void setGyroBias(const Vector3f &gyroBias)
ftype Vector15[15]
Definition: SoloGimbalEKF.h:67
Vector13 states
Vector3f delAng
float lastInnovation
uint32_t lastMagUpdate
float calcMagHeadingInnov()
ftype Matrix22[22][22]
Definition: SoloGimbalEKF.h:72
uint32_t StartTime_ms
ftype Vector5[5]
Definition: SoloGimbalEKF.h:59
ftype Vector3[3]
Definition: SoloGimbalEKF.h:58
Vector3f magData
struct SoloGimbalEKF::state_elements & state