pykinematics.imu.orientation.OrientationComplementaryFilter

class pykinematics.imu.orientation.OrientationComplementaryFilter(g=9.81, alpha=0.1, beta=0.1, compute_bias=True, bias_alpha=0.1, acc_thresh=0.1, gyr_thresh=0.2, delta_gyr_thresh=0.01, adaptive_gain=True, gain_error_thresh=(0.1, 0.2), interp_thresh=0.9, acc_corr=True)

Complementary filter for orientation estimation.

Parameters:
g : float, optional

Local value of gravitational acceleration. Default is 9.8 m/s^2.

alpha : float, optional

Acceleration complementary filter cut-off frequency. Default is 0.1.

beta : float, optional

Magnetic field complementary filter cut-off frequency. Default is 0.1.

compute_bias : bool, optional

Compute the bias of the angular velocity. Default is True.

bias_alpha : float, optional

Angular velocity bias gain. Default is 0.1

acc_thresh : float, optional

Threshold for determining still periods from acceleration for bias updating. Default is 0.1.

gyr_thresh : float, optional

Threshold for determining still periods from angular velocity for bias updating. Default is 0.2

delta_gyr_thresh : float, optional

Threshold for determining still periods from change since previous update of angular velocity for bias updating. Default is 0.01.

adaptive_gain : bool, optional

Use adaptive gain or not. Default is True.

gain_error_thresh : array_like, optional

Cutoff values for gain factor calculation. Default is (0.1, 0.2).

interp_thresh : float, optional

Below which value to use SLERP vs LERP. Default is 0.9

acc_corr : bool, optional

Correct acceleration by removing rotational acceleration. Default is True

References

Valenti et al. Keeping a Good Attitude: A Quaternion-Based Orientation Filter for IMU and MARGs. Sensors. 2015

Methods

run(self, acc, gyr, mag, dt, r) Run the orientation estimation over the data
run(self, acc, gyr, mag, dt, r)

Run the orientation estimation over the data

Parameters:
acc : numpy.ndarray

Nx3 array of accelerations.

gyr : numpy.ndarray

Nx3 array of angular velocities.

mag : numpy.ndarray

Nx3 array of magnetic field readings.

dt : float

Sampling time.

Attributes:
q_ : numpy.ndarray

Nx4 array of orientation estimates from the global frame to the local frame.