IMUs¶
These routines facilitate the calculation of 3d movement kinematics for recordings from inertial measurement units (IMUs).
They are implemented in an object oriented way. (Don’t worry if you have not used objects before, it won’t be a problem here!) All sensor implementations are based on the abstract base class “IMU_Base”. For each sensor, the corresponding method “get_data” has to be implemented, by sub-classing IMU_Base. Currently 5 sensor types are supported
XSens
xio (original, and NGIMU)
YEI
polulu
manual
The last one is not a “real” sensor, but allows the creation of an IMU-object with your own IMU-data, without defining a new class. To create a sensor object, choose one of the existing sensor classes, as demonstrated in the example below. You have to provide at least the file-name of the file containing the sensor data. Optionally, you can also provide:
R_init … initial orientation [default = np.eye(3)]
pos_init … initial position [default = np.ones(3)]
q_type … method to calculate orientation. The options are:
“analytical” [default] … analytical solution, using only acc and omega
“kalman” … quaternion Kalman filter, using acc, omega, and mag
“madgwick” … Madgwick algorithm, using acc, omega, and mag
“mahony” … Mahony algorithm, using, acc and omega, and mag
“None” … If you want to only read in the sensor data
Data are read in, and by default the orientation is automatically calculated based on the parameter “q_type” and using the function _calc_orientation.
Note: support vor “Vicon” has dropped, because the Vicon btk is no longer supported.
Base-Class & Methods¶
|
Abstract BaseClass for working with working with inertial measurement units (IMUs) A concrete class must be instantiated, which implements "get_data". |
Calculate the position, assuming that the orientation is already known. |
|
|
Retrieve "rate", "acc", "omega", "mag" from the input source and set the corresponding values of "self". |
|
Sets q_type, and automatically performs the relevant calculations. |
Classes and Functions for Sensor-Integration¶
imus.analytical()
… Calculate orientation and position analytically from angular velocity and linear accelerationimus.kalman()
… Calculate orientation from IMU-data using an Extended Kalman Filter
|
Madgwick's implementation of Mayhony's AHRS algorithm |
|
Madgwick's gradient descent filter. |
Details¶
This file contains the abstract base class “IMU_Base” for analyzing movements recordings with inertial measurement units (IMUs), as well as functions and classes for the evaluation of IMU-data..
The advantage of using an “abstract base class” is that it allows to write code that is independent of the IMU-sensor. All IMUs provide acceleration and angular velocities, and most of them also the direction of the local magnetic field. The specifics of each sensor are hidden in the sensor-object (specifically, in the “get_data” method which has to be implemented once for each sensor). Initialization of a sensor object includes a number of activities:
Reading in the data.
Making acceleration, angular_velocity etc. accessible in a sensor- independent way
Calculating duration, totalSamples, etc.
Calculating orientation (expressed as “quat”), with the method specified in “q_type”
- class imus.IMU_Base(in_file=None, q_type='analytical', R_init=array([[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]), calculate_position=True, pos_init=array([0., 0., 0.]), in_data=None)[source]¶
Abstract BaseClass for working with working with inertial measurement units (IMUs) A concrete class must be instantiated, which implements “get_data”. (See example below.)
- acc¶
3D linear acceleration [m/s**2]
- Type:
Nx3 array
- dataType¶
Type of data (commonly float)
- Type:
string
- duration¶
Duration of recording [sec]
- Type:
float
- mag¶
3D orientation of local magnectic field
- Type:
Nx3 array
- omega¶
3D angular velocity [rad/s]
- Type:
Nx3 array
- pos¶
3D position
- Type:
Nx3 array
- pos_init¶
Initial position. default is np.ones(3)
- Type:
3-vector
- quat¶
3D orientation
- Type:
Nx4 array
- q_type¶
Method of calculation for orientation quaternion
- Type:
string
- rate¶
Sampling rate [Hz]
- Type:
float
- R_init¶
Rotation matrix defining the initial orientation. Default is np.eye(3)
- Type:
3x3 array
- source¶
Name of data-file
- Type:
str
- totalSamples¶
Number of samples
- Type:
int
- vel¶
3D velocity
- Type:
Nx3 array
- Parameters:
inFile (string) – path- and file-name of data file / input source
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 [rad/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: float
sample rate [Hz]
Examples
>>> # Set the in-file, initial sensor orientation >>> in_file = r'tests/data/data_xsens.txt' >>> initial_orientation = np.array([[1,0,0], >>> [0,0,-1], >>> [0,1,0]]) >>> >>> # Choose a sensor >>> from skinematics.sensors.xsens import XSens >>> from skinematics.sensors.manual import MyOwnSensor >>> >>> # Only read in the data >>> data = XSens(in_file, q_type=None) >>> >>> # Read in and evaluate the data >>> sensor = XSens(in_file=in_file, R_init=initial_orientation) >>> >>> # By default, the orientation quaternion gets automatically calculated, >>> # using the option "analytical" >>> q_analytical = sensor.quat >>> >>> # Automatic re-calculation of orientation if "q_type" is changed >>> sensor.set_qtype('madgwick') >>> q_Madgwick = sensor.quat >>> >>> sensor.set_qtype('kalman') >>> q_Kalman = sensor.quat >>> >>> # Demonstrate how to fill up a sensor manually >>> in_data = {'rate':sensor.rate, >>> 'acc': sensor.acc, >>> 'omega':sensor.omega, >>> 'mag':sensor.mag} >>> my_sensor = MyOwnSensor(in_file='My own 123 sensor.', in_data=in_data)
- abstract get_data(in_file=None, in_data=None)[source]¶
Retrieve “rate”, “acc”, “omega”, “mag” from the input source and set the corresponding values of “self”. With some sensors, “rate” has to be provided, and is taken from “in_data”.
- set_qtype(type_value)[source]¶
Sets q_type, and automatically performs the relevant calculations. q_type determines how the orientation is calculated. If “q_type” is “None”, no orientation gets calculated; otherwise, the orientation calculation is performed with “_calc_orientation”, using the option “q_type”.
It has to be one of the following values:
analytical
kalman
madgwick
mahony
None
- class imus.Madgwick(rate=256.0, Beta=1.0, Quaternion=[1, 0, 0, 0])[source]¶
Madgwick’s gradient descent filter.
- Parameters:
rate (double) – sample rate [Hz]
Beta (double) – algorithm gain
Quaternion (array, shape (N,4)) – output quaternion describing the Earth relative to the sensor
- Update(Gyroscope, Accelerometer, Magnetometer)[source]¶
Calculate the best quaternion to the given measurement values.
- Parameters:
Gyroscope (array, shape (,3)) – Angular velocity [rad/s]
Accelerometer (array, shape (,3)) – Linear acceleration (Only the direction is used, so units don’t matter.)
Magnetometer (array, shape (,3)) – Orientation of local magenetic field. (Again, only the direction is used, so units don’t matter.)
- class imus.Mahony(rate=256.0, Kp=1.0, Ki=0, Quaternion=[1, 0, 0, 0])[source]¶
Madgwick’s implementation of Mayhony’s AHRS algorithm
- Parameters:
rate (double) – sample rate [Hz]
Kp (algorithm proportional gain)
Ki (algorithm integral gain)
Quaternion (output quaternion describing the Earth relative to the sensor)
- Update(Gyroscope, Accelerometer, Magnetometer)[source]¶
Calculate the best quaternion to the given measurement values.
- Parameters:
Gyroscope (array, shape (,3)) – Angular velocity [rad/s]
Accelerometer (array, shape (,3)) – Linear acceleration (Only the direction is used, so units don’t matter.)
Magnetometer (array, shape (,3)) – Orientation of local magenetic field. (Again, only the direction is used, so units don’t matter.)
- imus.analytical(R_initialOrientation=array([[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]), omega=array([[0., 0., 0.], [0., 0., 0.], [0., 0., 0.], [0., 0., 0.], [0., 0., 0.]]), initialPosition=array([0., 0., 0.]), accMeasured=array([[0., 0., 9.81], [0., 0., 9.81], [0., 0., 9.81], [0., 0., 9.81], [0., 0., 9.81]]), rate=100)[source]¶
Reconstruct position and orientation with an analytical solution, from angular velocity and linear acceleration. Assumes a start in a stationary position. No compensation for drift.
- Parameters:
R_initialOrientation (ndarray(3,3)) – Rotation matrix describing the initial orientation of the sensor, except a mis-orienation with respect to gravity
omega (ndarray(N,3)) – Angular velocity, in [rad/s]
initialPosition (ndarray(3,)) – initial Position, in [m]
accMeasured (ndarray(N,3)) – Linear acceleration, in [m/s^2]
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]
vel (ndarray(N,3)) – Velocity in space [m/s]
Example
>>> q1, pos1 = analytical(R_initialOrientation, omega, initialPosition, acc, rate)
- imus.kalman(rate, acc, omega, mag, D=[0.4, 0.4, 0.4], tau=[0.5, 0.5, 0.5], Q_k=None, R_k=None)[source]¶
Calclulate the orientation from IMU magnetometer data.
- Parameters:
rate (float) – sample rate [Hz]
acc ((N,3) ndarray) – linear acceleration [m/sec^2]
omega ((N,3) ndarray) – angular velocity [rad/sec]
mag ((N,3) ndarray) – magnetic field orientation
D ((,3) ndarray) – noise variance, for x/y/z [rad^2/sec^2] parameter for tuning the filter; defaults from Yun et al. can also be entered as list
tau ((,3) ndarray) – time constant for the process model, for x/y/z [sec] parameter for tuning the filter; defaults from Yun et al. can also be entered as list
Q_k (None, or (7,7) ndarray) – covariance matrix of process noises parameter for tuning the filter If set to “None”, the defaults from Yun et al. are taken!
R_k (None, or (7,7) ndarray) – covariance matrix of measurement noises parameter for tuning the filter; defaults from Yun et al. If set to “None”, the defaults from Yun et al. are taken!
- 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)
Sub-classing IMU-Base for your own sensor type¶
If you have your own data format, you have to implement the corresponding “get_data” method. You can base it on:
“xsens.py” … if all your data are in one file
“polulu.py” … if you have to manually enter data not stored by your program
“xio.py” … if your data are stored in multiple files
Existing Sensor Implementations¶
XIO¶
Import data saved with “x-IMU” sensors from x-io, through subclassing “IMU_Base” Note that the data are in two files:
a data-file
a reg-file
More info about the sensor on http://x-io.co.uk
- class sensors.xio.XIO(in_file=None, q_type='analytical', R_init=array([[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]), calculate_position=True, pos_init=array([0., 0., 0.]), in_data=None)[source]¶
Concrete class based on abstract base class IMU_Base
- get_data(in_file, in_data=None)[source]¶
Get the sampling rate, as well as the recorded data, and assign them to the corresponding attributes of “self”.
- Assigns the following properties
rate : rate
acc : acceleration
omega : angular_velocity
mag : mag_field_direction
packet_nr : packet_nr
- Parameters:
in_selection (string) – Directory containing all the data-files, or filename of one file in that directory
in_data (not used here)
- sensors.xio.read_datafile(in_file)[source]¶
Read data from an XIO “CalInertialAndMag”-file.
- Parameters:
in_file (string) – Has to be the name of the “CalInertialAndMag”-file.
- Returns:
out_list – Contains the following parameters:
acceleration
angular_velocity
mag_field_direction
packet_nr
- Return type:
list
x-io NGIMU¶
Import data saved with “NGIMU” sensors from x-io, through subclassing “IMU_Base” Note that the data are in two files:
a data-file
a reg-file
More info about the sensor on http://x-io.co.uk
- class sensors.xio_ngimu.NGIMU(in_file=None, q_type='analytical', R_init=array([[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]), calculate_position=True, pos_init=array([0., 0., 0.]), in_data=None)[source]¶
Concrete class based on abstract base class IMU_Base
- get_data(in_file, in_data=None)[source]¶
Get the sampling rate, as well as the recorded data, and assign them to the corresponding attributes of “self”. For the x-io.NGIMU, the data are stored in different files:
“Settings.txt” : contains all the sensor-settings
“sensors.csv” : contains the recorded sensor data
- Assigns the following properties:
rate : rate
acc : acceleration
omega : angular_velocity
mag : mag_field_direction
- Parameters:
in_selection (string) – Directory containing all the data-files, or filename of one file in that directory
in_data (not used here)
- sensors.xio_ngimu.read_datafile(in_file)[source]¶
Read data from an XIO “CalInertialAndMag”-file.
- Parameters:
in_file (string) – Has to be the name of the “sensors.csv”-file.
- Returns:
out_list – Contains the following parameters:
time [s]
acceleration [g]
angular_velocity [deg/s]
mag_field_direction [uT]
barometer [hPa]
- Return type:
list
- sensors.xio_ngimu.read_ratefile(reg_file)[source]¶
Read send-rates from an NGIMU sensor. “Disabled” channels have the “rate” set to “None”.
- Parameters:
in_file (string) – Has to be the “Registers”-file.
- Returns:
rates – Contains the send-rates for the following paramters: - sensors - magnitudes - quaternion - matrix - euler - linear - earth - altitude - temperature - humidity - battery - analogue - rssi
- Return type:
directory
XSens¶
Import data saved with XSens-sensors, through subclassing “IMU_Base”
YEI¶
Import data saved with yei-sensors, through subclassing “IMU_Base”
Polulu¶
Import data saved with polulu-sensors, through subclassing “IMU_Base”
https://www.pololu.com/product/2738 These are low-cost IMUS (<20 US$), where acceleration/gyroscope data are not sampled at the same time as the magnetic field data (just over 100 Hz). As a result, the interpolated sampling rate has to be set by hand.
- class sensors.polulu.Polulu(in_file=None, q_type='analytical', R_init=array([[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]]), calculate_position=True, pos_init=array([0., 0., 0.]), in_data=None)[source]¶
Concrete class based on abstract base class IMU_Base
- get_data(in_file, in_data=125)[source]¶
Get the sampling rate, as well as the recorded data, and assign them to the corresponding attributes of “self”.
- Parameters:
in_file (string) – Filename of the data-file
in_data (float) – Sampling rate (has to be provided!!)
Assigns
-------
rate (-)
acc (-)
omega (-)
mag (-)