Skip to content

Commit affbd28

Browse files
committed
downgrade to v1.3.0
1 parent b056478 commit affbd28

File tree

7 files changed

+74
-84
lines changed

7 files changed

+74
-84
lines changed

README.md

Lines changed: 24 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,23 +1,39 @@
11
# 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:
33

4-
$\ \overrightarrow{a_{rel}} = \overrightarrow{a_{local}} - (0,0,1) $
5-
6-
$\ K_{\sigma} = {\alpha}/(1 + \frac{ {\sigma}^2 }{ {\sigma}_{acc}^2 } ) $
4+
__Mahony:__
5+
$\ E_{k} = \theta_{accel} - \theta_{k-1} $
76

8-
$\ {\sigma}^2 = | \overrightarrow{a_{rel}} |^2 + K_{\sigma}{\sigma}^2 $
7+
$\ I_{k} = I_{k-1} + {E_{k}}{\Delta t} $
98

10-
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:
9+
$\ \theta_{k} = \theta_{k-1} + \dot{\theta}{\Delta t} + K_{p}E_{k} + K_{i}I_{k} $
1110

11+
__Modified Mahony:__ (this filter)
1212
$\ E_{k} = \theta_{accel} - \theta_{k-1} $
1313

14-
$\ \theta_{k} = \theta_{k-1} + \dot{\theta}{\Delta t} + K_{\sigma}E_{k} $
14+
$\ I_{k} = K_{p}{E_{k}} + (1 - K_{c})I_{k-1} $
15+
16+
$\ \theta_{k} = \theta_{k-1} + \dot{\theta}{\Delta t} + I_{k} $
17+
18+
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:
23+
24+
$\ \overrightarrow{a_{rel}} = \overrightarrow{a_{local}} - (0,0,1) $
25+
26+
$\ K_{\sigma} = 1/(1 + \frac{ {\sigma}^2 }{ {\sigma}_{acc}^2 } ) $
27+
28+
$\ {\sigma}^2 = | \overrightarrow{a_{rel}} |^2 + K_{\sigma}{\sigma}^2 $
29+
30+
$\ E_{k} = K_{\sigma} E_{k} $
1531

1632
As the filter uses a quaternion to encode rotations, it's easy to perform coordinate transformations. The library has functions to:
1733
- Transfor a vector to the local or global frame.
1834
- Get the unit vectors of the X, Y and Z axes in the local or global frame.
1935

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.
2137

2238
# Dependecies
2339
This library depends on the [vector_datatype](https://github.com/RCmags/vector_datatype) library.

examples/heading/heading.ino

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -10,18 +10,18 @@ basicMPU6050<> imu;
1010
imuFilter fusion;
1111

1212
void setup() {
13-
Serial.begin(38400);
13+
// Initialize filter:
14+
fusion.setup( imu.ax(), imu.ay(), imu.az() );
1415

1516
// Calibrate imu
1617
imu.setup();
1718
imu.setBias();
18-
19-
// Initialize filter:
20-
fusion.setup( imu.ax(), imu.ay(), imu.az() );
2119

2220
// Rotate heading:
2321
float angle = 45 * DEG_TO_RAD; // angle in radians to rotate heading about z-axis
2422
fusion.rotateHeading( angle, LARGE_ANGLE ); // Can choose LARGE_ANGLE or SMALL_ANGLE approximation
23+
24+
Serial.begin(38400);
2525
}
2626

2727
void loop() {

examples/output/output.ino

Lines changed: 13 additions & 44 deletions
Original file line numberDiff line numberDiff line change
@@ -1,68 +1,37 @@
11
/*
22
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+
*/
44

55
#include <basicMPU6050.h> // Library for IMU sensor. See this link: https://github.com/RCmags/basicMPU6050
66
#include <imuFilter.h>
77

8-
// Gyro settings:
9-
#define LP_FILTER 3 // Low pass filter. Value from 0 to 6
10-
#define GYRO_SENS 0 // Gyro sensitivity. Value from 0 to 3
11-
#define ACCEL_SENS 0 // Accelerometer sensitivity. Value from 0 to 3
12-
#define ADDRESS_A0 LOW // I2C address from state of A0 pin. A0 -> GND : ADDRESS_A0 = LOW
13-
// A0 -> 5v : ADDRESS_A0 = HIGH
14-
// Accelerometer offset:
15-
constexpr int AX_OFFSET = 552; // Use these values to calibrate the accelerometer. The sensor should output 1.0g if held level.
16-
constexpr int AY_OFFSET = -241; // These values are unlikely to be zero.
17-
constexpr int AZ_OFFSET = -3185;
18-
19-
// Output scale:
20-
constexpr float AX_SCALE = 1.00457; // Multiplier for accelerometer outputs. Use this to calibrate the sensor. If unknown set to 1.
21-
constexpr float AY_SCALE = 0.99170;
22-
constexpr float AZ_SCALE = 0.98317;
23-
24-
constexpr float GX_SCALE = 0.99764; // Multiplier to gyro outputs. Use this to calibrate the sensor. If unknown set to 1.
25-
constexpr float GY_SCALE = 1.0;
26-
constexpr float GZ_SCALE = 1.01037;
27-
28-
// Bias estimate:
29-
#define GYRO_BAND 35 // Standard deviation of the gyro signal. Gyro signals within this band (relative to the mean) are suppresed.
30-
#define BIAS_COUNT 5000 // Samples of the mean of the gyro signal. Larger values provide better calibration but delay suppression response.
31-
32-
//-- Set the template parameters:
33-
34-
basicMPU6050<LP_FILTER, GYRO_SENS, ACCEL_SENS, ADDRESS_A0,
35-
AX_OFFSET, AY_OFFSET, AZ_OFFSET,
36-
&AX_SCALE, &AY_SCALE, &AZ_SCALE,
37-
&GX_SCALE, &GY_SCALE, &GZ_SCALE,
38-
GYRO_BAND, BIAS_COUNT
39-
>imu;
8+
basicMPU6050<> imu;
409

4110
// =========== Settings ===========
4211
imuFilter fusion;
4312

44-
#define GAIN 0.5 /* Fusion gain, value between 0 and 1 - Determines orientation correction with respect to gravity vector.
13+
#define GAIN 0.1 /* Fusion gain, value between 0 and 1 - Determines orientation correction with respect to gravity vector.
4514
If set to 1 the gyroscope is dissabled. If set to 0 the accelerometer is dissabled (equivant to gyro-only) */
4615

47-
#define SD_ACCEL 0.2 /* Standard deviation of acceleration. Accelerations relative to (0,0,1)g outside of this band are suppresed.
16+
#define SD_ACCEL 0.1 /* Standard deviation of acceleration. Accelerations relative to (0,0,1)g outside of this band are suppresed.
4817
Accelerations within this band are used to update the orientation. [Measured in g-force] */
4918

5019
#define FUSION true /* Enable sensor fusion. Setting to "true" enables gravity correction */
5120

5221
void setup() {
53-
Serial.begin(38400);
54-
55-
// Calibrate imu
56-
imu.setup();
57-
imu.setBias();
58-
59-
#if FUSION
60-
Set quaternion with gravity vector
22+
#if FUSION
23+
// Set quaternion with gravity vector
6124
fusion.setup( imu.ax(), imu.ay(), imu.az() );
6225
#else
63-
Just use gyro
26+
// Just use gyro
6427
fusion.setup();
6528
#endif
29+
30+
// Calibrate imu
31+
imu.setup();
32+
imu.setBias();
33+
34+
Serial.begin(38400);
6635
}
6736

6837
void loop() {

examples/vector_output/vector_output.ino

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -26,14 +26,14 @@ void printQuat( quat_t q ) {
2626
}
2727

2828
void setup() {
29-
Serial.begin(38400);
30-
29+
// Initialize filter:
30+
fusion.setup( imu.ax(), imu.ay(), imu.az() );
31+
3132
// Calibrate imu
3233
imu.setup();
3334
imu.setBias();
34-
35-
// Initialize filter:
36-
fusion.setup( imu.ax(), imu.ay(), imu.az() );
35+
36+
Serial.begin(38400);
3737
}
3838

3939
void loop() {

library.properties

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11
name=imuFilter
2-
version=1.4.0
2+
version=1.3.0
33
author=RCmags <[email protected]>
44
maintainer=RCmags <[email protected]>
55
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.
77
category=Device Control
88
url=https://github.com/RCmags/imuFilter
99
architectures=*

src/imuFilter.cpp

Lines changed: 23 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -3,14 +3,14 @@
33
//----------------- Initialization -------------------
44

55
float imuFilter::updateTimer() {
6-
uint32_t time_now = micros();
7-
uint32_t change_time = time_now - last_time;
8-
last_time = time_now;
6+
uint32_t change_time = uint32_t( micros() - last_time );
7+
last_time = micros();
98
return float(change_time)*1e-6;
109
}
1110

1211
void imuFilter::setup() {
1312
var = 0;
13+
s = {0,0,0};
1414
q = {1,0,0,0};
1515
last_time = micros();
1616
}
@@ -54,25 +54,29 @@ void imuFilter::update( float gx, float gy, float gz,
5454
// Update Timer
5555
float dt = updateTimer();
5656

57-
// check global acceleration:
57+
// check global acceleration
5858
vec3_t accel = {ax, ay, az};
59-
vec3_t acrel = q.rotate(accel, GLOBAL_FRAME) - vec3_t(0,0,1);
60-
61-
// kalmal filter:
62-
const float INV_VAR = 1.0/( SD_ACC * SD_ACC );
63-
float error = acrel.dot(acrel); // deviation from vertical
64-
65-
float gain = ALPHA * dt;
66-
gain = gain/(1 + var*INV_VAR); // kalman gain
67-
var = error + var*gain; // variance of error
59+
vec3_t error = q.rotate(accel, GLOBAL_FRAME) - vec3_t(0,0,1);
60+
float error_mag = error.dot(error); // deviation from (0,0,1)g
6861

62+
const float INV_VAR = 1.0/( SD_ACC * SD_ACC );
63+
float gain = 1.0/(1 + var*INV_VAR); // kalman gain
64+
var = error_mag + var*gain; // variance of error
65+
6966
// error about vertical
7067
vec3_t vz = q.axisZ(LOCAL_FRAME);
7168
vec3_t ve = accel.norm();
7269
ve = ve.cross(vz);
7370

74-
// Rotation increment
75-
vec3_t da = vec3_t(gx, gy, gz)*dt + ve*gain;
71+
// filter gains
72+
const float KP = ALPHA*ALPHA;
73+
float kp = KP*dt; // spring constant
74+
float kc = sqrt(INV_Q_FACTOR*kp); // damping constant
75+
kp *= gain; // modulate error with kalman gain
76+
77+
// Rotation increment
78+
s += ve*kp - s*kc; // target angular rate
79+
vec3_t da = vec3_t(gx, gy, gz)*dt + s;
7680
quat_t dq; dq.setRotation(da, SMALL_ANGLE);
7781

7882
// Multiply and normalize Quaternion
@@ -119,14 +123,14 @@ vec3_t imuFilter::projectVector( vec3_t vec, const bool TO_WORLD ) {
119123

120124
//------------------ Euler Angles -------------------
121125

122-
float imuFilter::roll() { // x-axis
126+
float imuFilter::roll() {
123127
vec3_t v = q.v;
124-
float y = 2*( q.w*v.x + v.y*v.z );
128+
float y = 2*( q.w*v.x + v.y*v.z );
125129
float x = 1 - 2*( v.x*v.x + v.y*v.y );
126130
return atan2( y, x );
127131
}
128132

129-
float imuFilter::pitch() { // y-axis
133+
float imuFilter::pitch() {
130134
constexpr float PI_2 = PI*0.5;
131135
vec3_t v = q.v;
132136
float a = 2*( v.y*q.w - v.z*v.x );
@@ -139,7 +143,7 @@ float imuFilter::pitch() { // y-axis
139143
}
140144
}
141145

142-
float imuFilter::yaw() { // z-axis
146+
float imuFilter::yaw() {
143147
vec3_t v = q.v;
144148
float y = 2*( v.z*q.w + v.x*v.y );
145149
float x = 1 - 2*( v.y*v.y + v.z*v.z );

src/imuFilter.h

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,13 +7,14 @@
77
//------------------ Coefficients --------------------
88

99
#define INV_Q_FACTOR 2 // Filter damping. A smaller value leads to faster response but more oscillations.
10-
#define DEFAULT_GAIN 0.5 // Default filter gain.
11-
#define DEFAULT_SD 0.2 // Default standard deviation in acceleration. [g-force]
10+
#define DEFAULT_GAIN 0.1 // Default filter gain. A faster value
11+
#define DEFAULT_SD 0.1 // Default standard deviation in acceleration. [g-force]
1212

1313
//---------------- Class definition ------------------
1414

1515
class imuFilter {
1616
private:
17+
vec3_t s;
1718
quat_t q;
1819
float var;
1920
uint32_t last_time;

0 commit comments

Comments
 (0)