IMUs

These routines facilitate the calculation of 3d movement kinematics for recordings from inertial measurement units (IMUs).

Functions

General

  • imus.data_import() ... Read in Rate and stored 3D parameters from XSens IMUs

IMUs

  • imus.calc_QPos() ... Calculate orientation and position, from angular velocity and linear acceleration
  • imus.kalman_quat() ... Calculate orientation from IMU-data using an Extended Kalman Filter

Class

imus.IMU([inFile, inData]) Class for working with working with inertial measurement units (IMUs)

Methods

imus.IMU.calc_orientation(R_initialOrientation) Calculate the current orientation
imus.IMU.calc_position(initialPosition) Calculate the position, assuming that the orientation is already known.
imus.IMU.setData(data) Set the properties of an IMU-object.

Class

imus.MadgwickAHRS([SamplePeriod, Beta, ...])

Class

imus.MahonyAHRS([SamplePeriod, Kp, Ki, ...]) Madgwick’s implementation of Mayhony’s AHRS algorithm

Details

Utilities for movements recordins with inertial measurement units (IMUs)

class imus.IMU(inFile=None, inData=None)[source]

Class for working with working with inertial measurement units (IMUs)

An IMU object can be initialized
  • by giving a filename
  • by providing measurement data and a samplerate
  • without giving any parameter; in that case the user is prompted to select an infile
Parameters:
  • inFile (string) – path- and file-name of infile, if you get the sound from a file.
  • inData (dictionary) –

    The following fields are required:

    acc : (N x 3) array
    Linear acceleration [m/s^2], in the x-, y-, and z-direction
    omega : (N x 3) array
    Angular velocity [deg/s], about the x-, y-, and z-axis
    [mag] : (N x 3) array (optional)
    Local magnetic field, in the x-, y-, and z-direction
    rate: integer
    sample rate [Hz]

Notes

IMU-Properties:
  • source
  • acc
  • omega
  • mag
  • rate
  • totalSamples
  • duration
  • dataType

Examples

>>> myimu = IMU(r'.\Data\Walking_02.txt')
>>>
>>> initialOrientation = np.array([[1,0,0],
>>>                                [0,0,-1],
>>>                                [0,1,0]])
>>> initialPosition = np.r_[0,0,0]
>>>
>>> myimu.calc_orientation(initialOrientation)
>>> q_simple = myimu.quat[:,1:]
>>>
>>> calcType = 'Madgwick'
>>> myimu.calc_orientation(initialOrientation, type=calcType)
>>> q_Kalman = myimu.quat[:,1:]
calc_orientation(R_initialOrientation, type='quatInt')[source]

Calculate the current orientation

Parameters:
  • R_initialOrientation (3x3 array) – approximate alignment of sensor-CS with space-fixed CS
  • type (string) –
    • ‘quatInt’ ...... quaternion integration of angular velocity
    • ‘Kalman’ ..... quaternion Kalman filter
    • ‘Madgwick’ .. gradient descent method, efficient
    • ‘Mahony’ ... Formula from Mahony, as implemented by Madgwick
calc_position(initialPosition)[source]

Calculate the position, assuming that the orientation is already known.

setData(data)[source]

Set the properties of an IMU-object.

class imus.MahonyAHRS(SamplePeriod=0.00390625, Kp=1.0, Ki=0, Quaternion=[1, 0, 0, 0])[source]

Madgwick’s implementation of Mayhony’s AHRS algorithm

Update(Gyroscope, Accelerometer, Magnetometer)[source]

Calculate the best quaternion to the given measurement values.

imus.calc_QPos(R_initialOrientation, omega, initialPosition, accMeasured, rate)[source]

Reconstruct position and orientation, from angular velocity and linear acceleration. Assumes a start in a stationary position. No compensation for drift.

Parameters:
  • omega (ndarray(N,3)) – Angular velocity, in [rad/s]
  • accMeasured (ndarray(N,3)) – Linear acceleration, in [m/s^2]
  • initialPosition (ndarray(3,)) – initial Position, in [m]
  • R_initialOrientation (ndarray(3,3)) – Rotation matrix describing the initial orientation of the sensor, except a mis-orienation with respect to gravity
  • rate (float) – sampling rate, in [Hz]
Returns:

  • q (ndarray(N,3)) – Orientation, expressed as a quaternion vector
  • pos (ndarray(N,3)) – Position in space [m]

Example

>>> q1, pos1 = calc_QPos(R_initialOrientation, omega, initialPosition, acc, rate)
imus.import_data(inFile, type='XSens', paramList=[])[source]

Read in Rate and stored 3D parameters from XSens IMUs

Parameters:
  • inFile (string) – Path and name of input file
  • paramList (list of strings) – Starting names of stored parameters
Returns:

  • List, containing
  • rate (float) – Sampling rate
  • [List of x/y/z Parameter Values]

Examples

>>> data = getXSensData(fullInFile, ['Acc', 'Gyr'])
>>> rate = data[0]
>>> accValues = data[1]
>>> Omega = data[2]
imus.kalman_quat(rate, acc, gyr, mag)[source]

Calclulate the orientation from IMU magnetometer data.

Parameters:
  • rate (float) – sample rate [Hz]
  • acc ((N,3) ndarray) – linear acceleration [m/sec^2]
  • gyr ((N,3) ndarray) – angular velocity [rad/sec]
  • mag ((N,3) ndarray) – magnetic field orientation
Returns:

qOut – unit quaternion, describing the orientation relativ to the coordinate system spanned by the local magnetic field, and gravity

Return type:

(N,4) ndarray

Notes

Based on “Design, Implementation, and Experimental Results of a Quaternion-Based Kalman Filter for Human Body Motion Tracking” Yun, X. and Bachman, E.R., IEEE TRANSACTIONS ON ROBOTICS, VOL. 22, 1216-1227 (2006)