uutzinger / pyIMU

Python implementation of **Quaternion** and **Vector** math for Attitude and Heading Reference System (AHRS) as well as **motion** (acceleration, speed, position) estimation based on a Inertial Measurement Unit (IMU) (accelerometer, gyroscope and optional magnetometer).
MIT License
14 stars 2 forks source link

pyIMU

Python implementation of Quaternion and Vector math for Attitude and Heading Reference System (AHRS) as well as motion (acceleration, speed, position) estimation based on a Inertial Measurement Unit (IMU) consisting of an accelerometer, gyroscope and optional magnetometer.

The geometry conventions used in this implementation are from a pilots point of view:

The motion class has not yet been tested with hardware.

Install

Download the library and pip3 install -e . or omit the -e switch to install into python's site packages.

pyIMU.madgwick

Contains pose sensor fusion based on Sebastian Madgwick dissertation work and work by Mario Garcia as well as work by Richardson Tech (RTIMU).

There is newer implementation based on an alternative approach in the Madgwick thesis which is implemented in C with a Python API.

Original Code can be found here: https://x-io.co.uk/open-source-imu-and-ahrs-algorithms/

Magdwick Class

Incremental sensor fusion to compute pose quaternion from accelerometer, gyroscope and optional magnetometer.

Example:

from pyIMU.madgwick import Madgwick
madgwick = Madgwick(frequency=150.0, gain=0.033)
madgwick = Madgwick(dt=1/150.0, gain_imu=0.033)
madgwick = Madgwick()
type(madgwick.q)

# provide time increment dt based on time expired between each sensor reading
madgwick.update(gyr=gyro_data, acc=acc_data, dt=0.01)
madgwick.update(gyr=gyro_data, acc=acc_data, mag=mag_data, dt=0.01)
# access the quaternion
madgwick.q
# or take the return value of the update function

pyIMU.motion

Motion Class

Motion estimation based on IMU data. The implementation is inspired by Gate tracking

Example:

from pyIMU.motion import motion
estimator = motion(declination=9.27, latitude=32.253460, altitude=730, magfield=47392.3)

...
timestamp = time.time()
estimator.update(acc=acc, gyr=gyr, mag=mag, timestamp=timestamp)

pyIMU.quaternion

Contains Quaternion and Vector3d.

Quaternion Class

There are many implementations for quaternion math in python. This one is simple.

q = [w,x,y,z]

It supports operations with quaternion, ndarray, scalar, Vector3D

The operations supported are:

Vector3D Class

Vector class to support quaternions, rotations and manipulating sensor readings.

The class supports

pyIMU.utilities

General Utility

RunningAverage

Running average filter providing average and variance.

Vector and Quaternion Support Routines

Conversions:

Estimated quaternion based on gravity and magnetometer readings and assumption sensor is not moving.

Acceleration:

Gravity

Heading

Calibration

See freeIMUCal repo

Dependencies