What Is a Complementary Filter?
A complementary filter is a technique for optimally combining outputs from two sensors with different noise characteristics in the frequency domain. It applies a high-pass filter to one sensor and a low-pass filter to the other, designed so that their sum equals unity across all frequencies.
The most common application is sensor fusion of gyroscopes and accelerometers in an IMU (Inertial Measurement Unit).
| Sensor | Strength | Weakness |
|---|---|---|
| Gyroscope | Accurate for short-term changes | Drift accumulates over time |
| Accelerometer | Stable over long periods (gravity reference) | Sensitive to vibration and noise |
Gyroscopes compute angle by integrating angular velocity, so bias errors accumulate as drift (low-frequency error). Accelerometers can determine tilt from the gravity vector but are susceptible to vibration and translational acceleration (high-frequency noise).
The complementary filter exploits this complementary nature: it extracts high-frequency components from the gyroscope and low-frequency components from the accelerometer, canceling the weaknesses of both.
Key Application Areas
- Drones and multicopters: Attitude estimation (pitch and roll angles)
- Robotics: Posture stabilization for bipedal robots
- Smartphones: Screen rotation, AR/VR head tracking
- Vehicle control: Sideslip angle estimation
Theory
Complementarity of High-Pass and Low-Pass Filters
The core principle of the complementary filter is that the high-pass filter \(H_{HPF}(z)\) and low-pass filter \(H_{LPF}(z)\) satisfy the following relationship:
\[H_{HPF}(z) + H_{LPF}(z) = 1 \tag{1}\]This property ensures that the combined sensor output is reconstructed without distortion across the entire frequency band.
Transfer Function of a First-Order Complementary Filter
Define the first-order low-pass filter transfer function as:
\[H_{LPF}(z) = \frac{(1-\alpha)}{1 - \alpha z^{-1}} \tag{2}\]From the complementary condition \((1)\), the high-pass filter becomes:
\[H_{HPF}(z) = 1 - H_{LPF}(z) = \frac{1 - z^{-1}}{1 - \alpha z^{-1}} \tag{3}\]The complementary filter output for gyroscope output \(X_{gyro}(z)\) and accelerometer output \(X_{accel}(z)\) is:
\[Y(z) = H_{HPF}(z) \cdot X_{gyro}(z) + H_{LPF}(z) \cdot X_{accel}(z) \tag{4}\]Time-Domain Update Equation
Taking the inverse Z-transform of equation \((4)\) yields the following recursive update equation:
\[\theta[n] = \alpha \left(\theta[n-1] + \dot{\theta}_{gyro}[n] \cdot \Delta t\right) + (1 - \alpha) \cdot \theta_{accel}[n] \tag{5}\]where:
- \(\theta[n]\): Current estimated angle
- \(\dot{\theta}_{gyro}[n]\): Gyroscope angular velocity output
- \(\theta_{accel}[n]\): Angle computed from accelerometer
- \(\Delta t\): Sampling period
- \(\alpha\): Filter coefficient (\(0 < \alpha < 1\))
Equation \((5)\) can be interpreted intuitively:
- First term: Weights the gyroscope integration by \(\alpha\) (high-pass filter effect)
- Second term: Weights the accelerometer angle by \((1-\alpha)\) (low-pass filter effect)
Relationship Between Time Constant \(\tau\) and Filter Coefficient \(\alpha\)
The parameter \(\alpha\) is determined from the time constant \(\tau\) and sampling period \(\Delta t\):
\[\alpha = \frac{\tau}{\tau + \Delta t} \tag{6}\]The physical meaning of the time constant \(\tau\) is:
- Large \(\tau\) (\(\alpha \to 1\)): Greater gyroscope contribution. Good short-term response but slow drift correction
- Small \(\tau\) (\(\alpha \to 0\)): Greater accelerometer contribution. Fast drift correction but susceptible to vibration noise
The crossover frequency \(f_c\) (where LPF and HPF gains are equal) is:
\[f_c = \frac{1}{2\pi\tau} \tag{7}\]Frequency Response Analysis
Analyzing the complementary filter’s frequency response confirms that the LPF and HPF gains cross at the crossover frequency \(f_c\), and their sum remains at 0 dB across all frequencies.
import numpy as np
import matplotlib.pyplot as plt
from scipy import signal
# --- Parameters ---
fs = 100.0 # Sampling frequency [Hz]
dt = 1.0 / fs
tau = 1.0 # Time constant [s]
alpha = tau / (tau + dt)
# --- Transfer function definition ---
# LPF: H_LPF(z) = (1-alpha) / (1 - alpha*z^{-1})
b_lpf = [1 - alpha]
a_lpf = [1, -alpha]
# HPF: H_HPF(z) = (1 - z^{-1}) / (1 - alpha*z^{-1})
b_hpf = [1, -1]
a_hpf = [1, -alpha]
# --- Frequency response ---
w_lpf, h_lpf = signal.freqz(b_lpf, a_lpf, worN=4096, fs=fs)
w_hpf, h_hpf = signal.freqz(b_hpf, a_hpf, worN=4096, fs=fs)
# Combined frequency response
h_sum = h_lpf + h_hpf
fc = 1.0 / (2 * np.pi * tau) # Crossover frequency
# --- Plot ---
fig, (ax1, ax2) = plt.subplots(2, 1, figsize=(10, 8))
# Gain characteristics
ax1.semilogx(w_lpf, 20 * np.log10(np.abs(h_lpf) + 1e-10),
label='LPF (Accelerometer)', linewidth=2)
ax1.semilogx(w_hpf, 20 * np.log10(np.abs(h_hpf) + 1e-10),
label='HPF (Gyroscope)', linewidth=2)
ax1.semilogx(w_lpf, 20 * np.log10(np.abs(h_sum) + 1e-10),
label='Sum (HPF + LPF)', linewidth=2, linestyle='--', color='black')
ax1.axvline(fc, color='r', linestyle=':', alpha=0.7,
label=f'$f_c$ = {fc:.3f} Hz')
ax1.axhline(-3, color='gray', linestyle=':', alpha=0.5, label='-3 dB')
ax1.set_xlabel('Frequency [Hz]')
ax1.set_ylabel('Gain [dB]')
ax1.set_title(f'Complementary Filter Frequency Response (τ={tau} s, α={alpha:.4f})')
ax1.legend()
ax1.grid(True, which='both', alpha=0.3)
ax1.set_xlim([0.001, fs / 2])
ax1.set_ylim([-40, 5])
# Phase characteristics
ax2.semilogx(w_lpf, np.angle(h_lpf, deg=True), label='LPF', linewidth=2)
ax2.semilogx(w_hpf, np.angle(h_hpf, deg=True), label='HPF', linewidth=2)
ax2.axvline(fc, color='r', linestyle=':', alpha=0.7)
ax2.set_xlabel('Frequency [Hz]')
ax2.set_ylabel('Phase [degrees]')
ax2.set_title('Phase Response')
ax2.legend()
ax2.grid(True, which='both', alpha=0.3)
ax2.set_xlim([0.001, fs / 2])
plt.tight_layout()
plt.savefig('complementary_frequency_response.png', dpi=150, bbox_inches='tight')
plt.show()
The LPF and HPF gains cross at \(-3\) dB at the crossover frequency, and their sum stays at 0 dB (= 1) across all frequencies. This is why the filter is called “complementary.”
Python Implementation
IMU Sensor Simulation
We simulate realistic IMU sensors to verify the complementary filter’s effectiveness.
import numpy as np
import matplotlib.pyplot as plt
# --- Simulation parameters ---
fs = 100.0 # Sampling frequency [Hz]
dt = 1.0 / fs
T = 30.0 # Simulation duration [s]
t = np.arange(0, T, dt)
N = len(t)
# --- True angle (test signal) ---
# Slow sinusoidal motion + step change
theta_true = (
15.0 * np.sin(2 * np.pi * 0.1 * t) + # 0.1 Hz oscillation
5.0 * np.sin(2 * np.pi * 0.5 * t) + # 0.5 Hz oscillation
10.0 * (t > 15) # Step change at t=15s
)
# --- True angular velocity ---
omega_true = np.gradient(theta_true, dt)
# --- Gyroscope output (angular velocity + bias drift + noise) ---
gyro_bias = 0.5 # Bias [deg/s] (cause of drift)
gyro_noise_std = 2.0 # Noise standard deviation [deg/s]
gyro_output = omega_true + gyro_bias + gyro_noise_std * np.random.randn(N)
# --- Accelerometer output (angle + vibration noise) ---
accel_noise_std = 5.0 # Noise standard deviation [deg]
accel_output = theta_true + accel_noise_std * np.random.randn(N)
# --- Gyro-only angle estimation (integration) ---
theta_gyro = np.zeros(N)
theta_gyro[0] = theta_true[0]
for i in range(1, N):
theta_gyro[i] = theta_gyro[i - 1] + gyro_output[i] * dt
# --- Complementary filter ---
tau = 1.0 # Time constant [s]
alpha = tau / (tau + dt)
theta_comp = np.zeros(N)
theta_comp[0] = theta_true[0]
for i in range(1, N):
# Implementation of equation (5)
theta_comp[i] = alpha * (theta_comp[i - 1] + gyro_output[i] * dt) \
+ (1 - alpha) * accel_output[i]
# --- Comparison plot ---
fig, axes = plt.subplots(4, 1, figsize=(12, 14), sharex=True)
# True angle
axes[0].plot(t, theta_true, 'k-', linewidth=2, label='True angle')
axes[0].set_ylabel('Angle [deg]')
axes[0].set_title('True Angle')
axes[0].legend()
axes[0].grid(True, alpha=0.3)
# Gyro only
axes[1].plot(t, theta_gyro, 'r-', alpha=0.8, label='Gyro only (integration)')
axes[1].plot(t, theta_true, 'k--', alpha=0.5, label='True')
axes[1].set_ylabel('Angle [deg]')
axes[1].set_title('Gyroscope Only (drift accumulation)')
axes[1].legend()
axes[1].grid(True, alpha=0.3)
# Accelerometer only
axes[2].plot(t, accel_output, 'b-', alpha=0.5, label='Accelerometer only')
axes[2].plot(t, theta_true, 'k--', alpha=0.5, label='True')
axes[2].set_ylabel('Angle [deg]')
axes[2].set_title('Accelerometer Only (noisy)')
axes[2].legend()
axes[2].grid(True, alpha=0.3)
# Complementary filter
axes[3].plot(t, theta_comp, 'g-', linewidth=2, label=f'Complementary (α={alpha:.3f})')
axes[3].plot(t, theta_true, 'k--', alpha=0.5, label='True')
axes[3].set_ylabel('Angle [deg]')
axes[3].set_xlabel('Time [s]')
axes[3].set_title('Complementary Filter')
axes[3].legend()
axes[3].grid(True, alpha=0.3)
plt.tight_layout()
plt.savefig('complementary_filter_comparison.png', dpi=150, bbox_inches='tight')
plt.show()
# --- RMSE calculation ---
rmse_gyro = np.sqrt(np.mean((theta_gyro - theta_true) ** 2))
rmse_accel = np.sqrt(np.mean((accel_output - theta_true) ** 2))
rmse_comp = np.sqrt(np.mean((theta_comp - theta_true) ** 2))
print(f"RMSE (Gyro only): {rmse_gyro:.2f} deg")
print(f"RMSE (Accelerometer only): {rmse_accel:.2f} deg")
print(f"RMSE (Complementary): {rmse_comp:.2f} deg")
The gyro-only estimate diverges significantly from the true value over time due to bias drift, while the accelerometer-only estimate fluctuates heavily due to vibration noise. The complementary filter mitigates both issues, producing an estimate close to the true value.
Effect of Parameter \(\alpha\)
We analyze how different values of \(\alpha\) (time constant \(\tau\)) affect estimation accuracy.
# --- Comparison with different α (τ) values ---
tau_values = [0.1, 0.5, 1.0, 5.0, 10.0]
fig, axes = plt.subplots(2, 1, figsize=(12, 10))
for tau_val in tau_values:
alpha_val = tau_val / (tau_val + dt)
theta_est = np.zeros(N)
theta_est[0] = theta_true[0]
for i in range(1, N):
theta_est[i] = alpha_val * (theta_est[i - 1] + gyro_output[i] * dt) \
+ (1 - alpha_val) * accel_output[i]
rmse = np.sqrt(np.mean((theta_est - theta_true) ** 2))
axes[0].plot(t, theta_est, label=f'τ={tau_val}s (α={alpha_val:.4f}, RMSE={rmse:.2f}°)')
axes[0].plot(t, theta_true, 'k--', linewidth=2, alpha=0.7, label='True')
axes[0].set_ylabel('Angle [deg]')
axes[0].set_xlabel('Time [s]')
axes[0].set_title('Effect of Time Constant τ on Complementary Filter')
axes[0].legend(fontsize=8)
axes[0].grid(True, alpha=0.3)
# τ vs RMSE plot
tau_range = np.logspace(-2, 2, 100)
rmse_list = []
for tau_val in tau_range:
alpha_val = tau_val / (tau_val + dt)
theta_est = np.zeros(N)
theta_est[0] = theta_true[0]
for i in range(1, N):
theta_est[i] = alpha_val * (theta_est[i - 1] + gyro_output[i] * dt) \
+ (1 - alpha_val) * accel_output[i]
rmse_list.append(np.sqrt(np.mean((theta_est - theta_true) ** 2)))
axes[1].semilogx(tau_range, rmse_list, 'b-', linewidth=2)
axes[1].set_xlabel('Time Constant τ [s]')
axes[1].set_ylabel('RMSE [deg]')
axes[1].set_title('RMSE vs Time Constant τ')
axes[1].grid(True, which='both', alpha=0.3)
# Show optimal τ
optimal_idx = np.argmin(rmse_list)
optimal_tau = tau_range[optimal_idx]
optimal_rmse = rmse_list[optimal_idx]
axes[1].axvline(optimal_tau, color='r', linestyle='--',
label=f'Optimal τ={optimal_tau:.2f}s (RMSE={optimal_rmse:.2f}°)')
axes[1].legend()
plt.tight_layout()
plt.savefig('alpha_effect.png', dpi=150, bbox_inches='tight')
plt.show()
Guidelines for choosing \(\alpha\):
| \(\tau\) Range | \(\alpha\) Tendency | Characteristics |
|---|---|---|
| \(\tau < 0.5\) s | Small \(\alpha\) | Accelerometer-weighted. More noise but less drift |
| \(0.5 \le \tau \le 2\) s | Medium \(\alpha\) | Balanced. Suitable for most applications |
| \(\tau > 5\) s | Large \(\alpha\) | Gyroscope-weighted. Good response but more drift |
The optimal \(\tau\) depends on the sensor noise characteristics. If the gyroscope bias is large, use a smaller \(\tau\); if the accelerometer noise is large, use a larger \(\tau\).
Comparison with Kalman Filter
Both complementary filters and Kalman filters are used for sensor fusion, but they differ in design philosophy.
| Property | Complementary Filter | Kalman Filter |
|---|---|---|
| Parameters | \(\alpha\) (single) | \(Q, R, P\) (process and observation noise covariance) |
| Computational cost | Very low (add/multiply only) | Moderate (matrix operations) |
| Design complexity | Simple | Requires model definition |
| Optimality | Not optimal | Optimal under linear Gaussian assumptions |
| Adaptivity | Fixed parameters | Gain auto-adjusts |
| Nonlinear systems | Not supported | EKF/UKF available |
| Real-time suitability | Extremely high | High (embedded implementations exist) |
| Lines of code | ~5 lines | ~30-50 lines |
Selection guidelines:
- Resource-constrained microcontrollers (Arduino, etc.) — Complementary filter
- Known noise characteristics requiring optimal estimation — Kalman filter
- Prototyping and educational purposes — Complementary filter (easier to understand)
- Multi-sensor fusion (GPS + IMU, etc.) — Kalman filter
In fact, a first-order complementary filter can be viewed as a special case of the steady-state Kalman filter. When the Kalman gain converges to steady state, the update equation takes the same form as equation \((5)\).
Practical Applications
| Application | Fused Sensors | Typical \(\tau\) | Notes |
|---|---|---|---|
| Drone attitude control | Gyro + Accelerometer | 0.5–2 s | Pitch and roll angle estimation |
| Smartphone screen rotation | Gyro + Accelerometer | 0.2–1 s | Balance between responsiveness and stability |
| Vehicle yaw rate estimation | Gyro + GPS heading | 1–5 s | Compensates GPS low sample rate |
| Robot attitude estimation | Gyro + Accelerometer + Magnetometer | 0.5–2 s | 9-axis IMU for yaw angle estimation |
| Pedestrian dead reckoning | Gyro + Accelerometer + Barometer | 1–3 s | Indoor positioning attitude estimation |
| VR/AR head tracking | Gyro + Accelerometer + Camera | 0.1–0.5 s | Low latency is critical |
Related Articles
- Low-Pass Filter Design and Comparison: Moving Average, Butterworth, and Chebyshev - Covers the theoretical background of the LPF component in complementary filters.
- High-Pass Filter Design and Python Implementation - Covers the theoretical background of the HPF component in complementary filters.
- Kalman Filter Theory and Python Implementation - Explains the Kalman filter, positioned as a more advanced alternative to complementary filters.
- Frequency Characteristics of the Exponential Moving Average (EMA) Filter - The LPF part of the complementary filter is equivalent to EMA; this article explains its frequency characteristics.
- Adaptive Filter (LMS/RLS) Theory and Python Implementation - Covers adaptive filters that automatically adjust parameters based on the environment.
References
- Mahony, R., Hamel, T., & Pflimlin, J.-M. (2008). Nonlinear Complementary Filters on the Special Orthogonal Group. IEEE Transactions on Automatic Control, 53(5), 1203-1218.
- Higgins, W. T. (1975). A Comparison of Complementary and Kalman Filtering. IEEE Transactions on Aerospace and Electronic Systems, AES-11(3), 321-325.
- Arduino and MPU6050 Accelerometer and Gyroscope Tutorial
Related Tools
- DevToolBox - Free Developer Tools - Over 85 developer tools including JSON formatter, regex tester, and more
- CalcBox - Everyday Calculation Tools - Over 61 calculation tools including statistics, frequency conversion, and more