You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Copy file name to clipboardExpand all lines: README.md
+24-8Lines changed: 24 additions & 8 deletions
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -1,23 +1,39 @@
1
1
# imuFilter
2
-
This library fuses the outputs of an inertial measurement unit (IMU) and stores the heading as a quaternion. It uses a _kalman-like_filter to check the acceleration and see if it lies within a deviation from (0,0,1)g. If the acceleration is within this band, it will strongly correct the orientation. However, if the acceleration lies outside of this band, it will barely affect the orientation. To this end, the deviation from vertical is used to update the variance and kalman gain:
2
+
This library fuses the outputs of an inertial measurement unit (IMU) and stores the heading as a quaternion. It uses a _modified Mahony_filter that replaces the PI controller with a damped 2nd-order system. The proportional term was removed and the integral term was forced to decay to damp the system. The correction steps are as follows:
The kalman gain then scaled by a delay parameter and used to correct the attitude. This scaling allows the filter to act like a 1rst-order low pass filter that smoothens the acceleration at the cost of slower response:
The behavior of the modified filter is analogous to spring-mass system. Kp (stiffness) and Kc (damping) are related by the [Q-factor](https://en.wikipedia.org/wiki/Q_factor). This value is held constant, so the behavior of the filter is controlled by a single parameter (Kp):
19
+
20
+
$\ K_{c} = \sqrt{ K_{p}/Q } $
21
+
22
+
To improve the response of the filter, the acceleration is checked to see if it lies within a given deviation from its steady-state value (1g vertically). If the acceleration is within this band, it will strongly correct the orientation. However, if the acceleration lies outside of this band, it will barely affect the orientation. This is accomplished with a kalman-like filter that uses the deviation from vertical to update its variance and gain:
As the filter uses a quaternion to encode rotations, it's easy to perform coordinate transformations. The library has functions to:
17
33
- Transfor a vector to the local or global frame.
18
34
- Get the unit vectors of the X, Y and Z axes in the local or global frame.
19
35
20
-
Moreover, since a 6-axis IMU (gyro-accelerometer) cannot measure an absolute heading, a function is included to rotate the orientation about the vertical (yaw) axis. One can use vector operations to correct the heading with an additional sensor like a magnetometer.
36
+
Moreover, since a 6-axis IMU (gyro-accelerometer) cannot measure an absolute heading, a function is included to rotate the orientation about the vertical (yaw) axis. One can use vector operations to correct the heading with an additional sensor such a magnetometer.
21
37
22
38
# Dependecies
23
39
This library depends on the [vector_datatype](https://github.com/RCmags/vector_datatype) library.
Copy file name to clipboardExpand all lines: examples/output/output.ino
+13-44Lines changed: 13 additions & 44 deletions
Original file line number
Diff line number
Diff line change
@@ -1,68 +1,37 @@
1
1
/*
2
2
This sketch shows to initialize the filter and update it with the imu output. It also shows how to get the euler angles of the estimated heading orientation.
3
-
*/
3
+
*/
4
4
5
5
#include<basicMPU6050.h>// Library for IMU sensor. See this link: https://github.com/RCmags/basicMPU6050
6
6
#include<imuFilter.h>
7
7
8
-
// Gyro settings:
9
-
#defineLP_FILTER3// Low pass filter. Value from 0 to 6
10
-
#defineGYRO_SENS0// Gyro sensitivity. Value from 0 to 3
11
-
#defineACCEL_SENS0// Accelerometer sensitivity. Value from 0 to 3
12
-
#defineADDRESS_A0 LOW // I2C address from state of A0 pin. A0 -> GND : ADDRESS_A0 = LOW
13
-
// A0 -> 5v : ADDRESS_A0 = HIGH
14
-
// Accelerometer offset:
15
-
constexprint AX_OFFSET = 552; // Use these values to calibrate the accelerometer. The sensor should output 1.0g if held level.
16
-
constexprint AY_OFFSET = -241; // These values are unlikely to be zero.
17
-
constexprint AZ_OFFSET = -3185;
18
-
19
-
// Output scale:
20
-
constexprfloat AX_SCALE = 1.00457; // Multiplier for accelerometer outputs. Use this to calibrate the sensor. If unknown set to 1.
21
-
constexprfloat AY_SCALE = 0.99170;
22
-
constexprfloat AZ_SCALE = 0.98317;
23
-
24
-
constexprfloat GX_SCALE = 0.99764; // Multiplier to gyro outputs. Use this to calibrate the sensor. If unknown set to 1.
25
-
constexprfloat GY_SCALE = 1.0;
26
-
constexprfloat GZ_SCALE = 1.01037;
27
-
28
-
// Bias estimate:
29
-
#defineGYRO_BAND35// Standard deviation of the gyro signal. Gyro signals within this band (relative to the mean) are suppresed.
30
-
#defineBIAS_COUNT5000// Samples of the mean of the gyro signal. Larger values provide better calibration but delay suppression response.
sentence=Sensor fusion for IMU with quaternion based filter.
6
-
paragraph=Library to fuse the data of an inertial measurement unit (IMU). It uses a quaternion to encode the rotation and uses a kalman-like filter to correct the gyroscope with the accelerometer.
6
+
paragraph=Library to fuse the data of an inertial measurement unit (IMU). It uses a quaternion to encode the rotation and uses a modified Mahony filter to correct the gyroscope with the accelerometer.
0 commit comments