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
- 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
- “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.
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
Class¶
imus.IMU_Base ([in_file, q_type, R_init, …]) |
Abstract BaseClass for working with working with inertial measurement units (IMUs) A concrete class must be instantiated, which implements “get_data”. |
Abstract base class for analyzing movements recordings with inertial measurement units (IMUs)
- The advantage of this approach 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.]]), 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
¶ Nx3 array – 3D linear acceleration
-
dataType
¶ string – Type of data (commonly float)
-
duration
¶ float – Duration of recording [sec]
-
mag
¶ Nx3 array – 3D orientation of local magnectic field
-
omega
¶ Nx3 array – 3D angular velocity
-
pos_init
¶ 3-vector – Initial position. default is np.ones(3)
-
quat
¶ Nx4 array
-
q_type
¶ string – Method of calculation for orientation quaternion
-
rate
¶ int – Sampling rate
-
R_init
¶ 3x3 array – Rotation matrix defining the initial orientation. Default is np.eye(3)
-
source
¶ str – Name of data-file
-
totalSamples
¶ int – Number of samples
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 [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]
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 >>> 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.q_type = 'madgwick' >>> q_Madgwick = sensor.quat >>> >>> sensor.q_type = '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)
-
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”.
-
q_type
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
(SamplePeriod=0.00390625, Beta=1.0, Quaternion=[1, 0, 0, 0])[source]¶ Madgwick’s gradient descent filter.
Parameters: - SamplePeriod (double) – sample period [s]
- 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 (N,3)) – Angular velocity [rad/s]
- Accelerometer (array, shape (N,3)) – Linear acceleration (Only the direction is used, so units don’t matter.)
- Magnetometer (array, shape (N,3)) – Orientation of local magenetic field. (Again, only the direction is used, so units don’t matter.)
-
class
imus.
Mahony
(SamplePeriod=0.00390625, Kp=1.0, Ki=0, Quaternion=[1, 0, 0, 0])[source]¶ Madgwick’s implementation of Mayhony’s AHRS algorithm
Parameters: - SamplePeriod (sample period) –
- 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 (N,3)) – Angular velocity [rad/s]
- Accelerometer (array, shape (N,3)) – Linear acceleration (Only the direction is used, so units don’t matter.)
- Magnetometer (array, shape (N,3)) – Orientation of local magenetic field. (Again, only the direction is used, so units don’t matter.)
-
imus.
analytical
(rate, accMeasured, omega, initialPosition, R_initialOrientation)[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: - 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 = analytical(rate, acc, omega, initialPosition, R_initialOrientation)
-
imus.
kalman
(rate, acc, omega, mag)[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
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)
Methods¶
imus.IMU_Base.calc_position () |
Calculate the position, assuming that the orientation is already known. |
imus.IMU_Base.get_data ([in_file, in_data]) |
Retrieve “rate”, “acc”, “omega”, “mag” from the input source and set the corresponding values of “self”. |
Classes for Sensor-Integration¶
imus.Mahony ([SamplePeriod, Kp, Ki, Quaternion]) |
Madgwick’s implementation of Mayhony’s AHRS algorithm |
imus.Madgwick ([SamplePeriod, Beta, Quaternion]) |
Madgwick’s gradient descent filter. |
Functions¶
Data-Analysis¶
imus.analytical()
… Calculate orientation and position analytically from angular velocity and linear accelerationimus.kalman()
… Calculate orientation from IMU-data using an Extended Kalman Filter
Existing Sensor Implementations¶
Import data saved with xio-sensors, through subclassing “IMU_Base” Note that the data are in two files:
- a data-file
- a reg-file
-
class
sensors.xio.
XIO
(in_file=None, q_type='analytical', R_init=array([[ 1., 0., 0.], [ 0., 1., 0.], [ 0., 0., 1.]]), 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”.
Parameters: - in_selection (string) – Directory containing all the data-files, or filename of one file in that directory
- in_data (not used here) –
- Assigns –
- ------- –
- rate (-) –
- acc (-) –
- omega (-) –
- mag (-) –
- packet_nr (-) –
-
-
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
-
sensors.xio.
read_ratefile
(reg_file)[source]¶ Read send-rates from an XIO 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 different “params”. Return type: directory
Import data saved with XSens-sensors, through subclassing “IMU_Base”
-
class
sensors.xsens.
XSens
(in_file=None, q_type='analytical', R_init=array([[ 1., 0., 0.], [ 0., 1., 0.], [ 0., 0., 1.]]), pos_init=array([ 0., 0., 0.]), in_data=None)[source]¶ Concrete class based on abstract base class IMU_Base
Import data saved with yei-sensors, through subclassing “IMU_Base”
-
class
sensors.yei.
YEI
(in_file=None, q_type='analytical', R_init=array([[ 1., 0., 0.], [ 0., 1., 0.], [ 0., 0., 1.]]), pos_init=array([ 0., 0., 0.]), in_data=None)[source]¶ Concrete class based on abstract base class IMU_Base
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.]]), 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 (-) –
-