IMUs¶
These routines facilitate the calculation of 3d movement kinematics for recordings from inertial measurement units (IMUs). Currently data from 4 systems are supported:
- XSens
- xio
- YEI
- polulu
Functions¶
Data-Handling¶
imus.import_data()
... Read in rate and 3D parameters from different IMUs.sensors.xio.get_data()
... Read in rate and 3D parameters from xio sensors.sensors.xsens.get_data()
... Read in rate and 3D parameters from XSens sensors.sensors.yei.get_data()
... Read in rate and 3D parameters from YEI sensors.sensors.polulu.get_data()
... Read in rate and 3D parameters from polulu sensors.
Data-Analysis¶
imus.calc_QPos()
... Calculate orientation and position, from angular velocity and linear accelerationimus.kalman_quat()
... Calculate orientation from IMU-data using an Extended Kalman Filter
Classes for Sensor-Integration¶
imus.MahonyAHRS |
|
imus.MadgwickAHRS |
Details¶
Import data saved with XIO-sensors
-
sensors.xio.
get_data
(in_selection)[source]¶ Get the sampling rates, as well as the recorded data.
Parameters: in_selection (string) – Directory containing all the data-files, or filename of one file in that directory Returns: out_list – Contains the following parameters: - rate
- acceleration
- angular_velocity
- mag_field_direction
- packet_nr
Return type: list
-
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
-
sensors.xsens.
get_data
(in_file)[source]¶ Get the sampling rate, as well as the recorded data.
Parameters: in_file (string) – Filename of the data-file Returns: out_list – Contains the following parameters: - rate
- acceleration
- angular_velocity
- mag_field_direction
Return type: list
Import data saved with YEI-sensors
-
sensors.yei.
get_data
(in_file)[source]¶ Get the sampling rate, as well as the recorded data.
Parameters: in_file (string) – Filename of the data-file Returns: out_list – Contains the following parameters: - rate
- acceleration
- angular_velocity
- mag_field_direction
Return type: list
Import data saved with polulu-sensors 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.