Sensing¶
Microstrain IMU¶
- class epicallypowerful.sensing.microstrain.microstrain_imu.MicroStrainIMUs(imu_ids: list[str], rate: int = 1000, tare_on_startup: bool = False, timeout: float = 0.0002, num_retries: int = 10, verbose: bool = False)¶
Class for receiving data from MicroStrain IMUs. Getting data from each IMU is as simple as calling
get_data()with the respective serial identifier as the argument. The MicroStrain IMUs typically need no special configuration or calibration. The serial number used to identify the IMUs is typically found on top of the IMU, and is the last 6 digits following the period.In order to use this functionality, the low-level MSCL drivers need to be installed. Please see the tutorials on installing this, or directly consult the MSCL documentation (https://github.com/LORD-MicroStrain/MSCL).
Many helper functions are included in the
IMUDataclass to assist with getting data conveniently. Please see that documentation for all options.Example
from epicpower.sensing import MicroStrainIMUs ### Instantiation LEFT_THIGH = '154143' LEFT_SHANK = '133930' imus = MicroStrainIMUs([LEFT_THIGH, LEFT_SHANK]) ### Data # Complete Data thigh_data = imus.get_data(LEFT_THIGH) shank_data = imus.get_data(LEFT_SHANK) # Specific Orientation Channels thigh_roll = thigh_data.eul_x thigh_pitch = thigh_data.eul_y thigh_yaw = thigh_data.eul_z # Helpers for getting multiple relevant channels at once thigh_quaternion = thigh_data.quaternion thigh_euler = thigh_data.euler
- Parameters:
imu_ids (list) – dict of body segments and Microstrain serial numbers.
rate (int) – operational rate to set using internal MSCL library.
tare_on_startup (bool) – boolean for whether to automatically tare on startup. Default: False.
verbose (bool) – boolean for whether to print out additional information. Default: False.
num_retries (int) – number of times to retry connecting to an IMU if it fails the first time. Default: 10.
MPU9250 IMU¶
- class epicallypowerful.sensing.mpu9250.mpu9250_imu.MPU9250IMUs(imu_ids: dict[int, dict[str, int]], components=['acc', 'gyro'], acc_range_selector=2, gyro_range_selector=2, calibration_path='', verbose: bool = False)¶
Class for interfacing with the MPU9250 IMU using I2C communication, leveraging the TCA9548A multiplexer for communicating with multiple units at the same time.
- This class draws from the following resources:
MPU9250 calibration: https://github.com/makerportal/mpu92-calibration
TCA9548a multiplexer to connect multiple I2C devices with the same address: https://wolles-elektronikkiste.de/en/tca9548a-i2c-multiplexer
TDK InvenSense MPU9250 datasheet: https://invensense.tdk.com/wp-content/uploads/2015/02/PS-MPU-9250A-01-v1.1.pdf
PCA9548A datasheet: https://www.ti.com/lit/ds/symlink/pca9548a.pdf
Many helper functions are included in the
IMUDataclass to assist with getting data conveniently. Please see that documentation for all options.Example
from epicallypowerful.sensing import MPU9250IMUs ### Instantiation --- imu_ids = { 0: { 'bus': 1, 'channel': -1, # -1 --> no multiplexer, otherwise --> multiplexer channel 'address': 0x68, }, 1: { 'bus': 1, 'channel': -1, 'address': 0x69, }, } imus = MPU9250IMUs( imu_ids=imu_ids, components=['acc', 'gyro'], ) ### Stream data --- print(imus.get_data(imu_id=0).acc_x) print(imus.get_data(imu_id=1).acc_x)
- Parameters:
imu_ids (dict) – dictionary of each IMU and the I2C bus number, multiplexer channel (if used), and I2C address needed to access it.
components (list of strings) – list of MPU9250 sensing components to get. Could include acc, gyro, or mag. For example, components = [‘acc’,’gyro’,’mag’] would call on both the MPU9250’s MPU6050 and AK8963 boards, but components = [‘acc’,’gyro’] would only instantiate the MPU6050.
acc_range_selector (int) – index for range of accelerations to collect. Default: 2 (+/- 8 g), but can be: 0: +/- 2.0 g’s 1: +/- 4.0 g’s 2: +/- 8.0 g’s 3: +/- 16.0 g’s
gyro_range_selector (int) – index for range of angular velocities to collect. Default: 2 (+/- 1000.0 deg/s), but can be: 0: +/- 250.0 deg/s 1: +/- 500.0 deg/s 2: +/- 1000.0 deg/s 3: +/- 2000.0 deg/s
calibration_path (str) – path to JSON file with calibration values for IMUs to be connected. NOTE: this file indexes IMUs by which bus, multiplexer channel (if used), and I2C address they are connected to. Be careful not to use the calibration for one IMU connected in this way on another unit by mistake.
verbose (bool) – whether to print verbose output from IMU operation. Default: False.
- get_MPU6050_data(bus: SMBus, acc_range: float, gyro_range: float, address: int = 104) tuple[float]¶
Convert raw binary accelerometer, gyroscope, and temperature readings to floats.
- Parameters:
bus (smbus.SMBus) – I2C bus instance on the device.
acc_range (float) – +/- range of acceleration being read from MPU6050. Raw units are g’s (1 g = 9.81 m*s^-2).
gyro_range (float) – +/- range of gyro being read from MPU6050. Raw units are deg/s.
address (hex as int) – address of the MPU6050 subcircuit.
- Returns:
acceleration [g], gyroscope [deg/s], and temperature [Celsius] values.
- Return type:
acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z, temp (floats)
- get_AK8963_data(bus: SMBus, address=12, mag_coeffs=[]) tuple¶
Convert raw binary magnetometer readings to floats.
- Parameters:
bus (smbus.SMBus) – I2C bus instance on the device.
address (hex as int) – address of AK8963 sensor. Should always be default AK8963_ADDR value (defined outside function).
mag_coeffs (list of floats) – coefficients set from AK8963. Raw units are micro-T (uT).
- Returns:
magnetometer values (in uT).
- Return type:
mag_x, mag_y, mag_z (floats)
IMU Data¶
- class epicallypowerful.sensing.IMUData(m11: float = 0.0, m12: float = 0.0, m13: float = 0.0, m21: float = 0.0, m22: float = 0.0, m23: float = 0.0, m31: float = 0.0, m32: float = 0.0, m33: float = 0.0, ref_m11: float = 0.0, ref_m12: float = 0.0, ref_m13: float = 0.0, ref_m21: float = 0.0, ref_m22: float = 0.0, ref_m23: float = 0.0, ref_m31: float = 0.0, ref_m32: float = 0.0, ref_m33: float = 0.0, quat_x: float = 0.0, quat_y: float = 0.0, quat_z: float = 0.0, quat_w: float = 1.0, ef_quat_x: float = 0.0, ef_quat_y: float = 0.0, ef_quat_z: float = 0.0, ef_quat_w: float = 1.0, eul_x: float = 0.0, eul_y: float = 0.0, eul_z: float = 0.0, gyro_x: float = 0.0, gyro_y: float = 0.0, gyro_z: float = 0.0, acc_x: float = 0.0, acc_y: float = 0.0, acc_z: float = 0.0, mag_x: float = 0.0, mag_y: float = 0.0, mag_z: float = 0.0, temp: float = 0.0, timestamp: float = 0.0)¶
Dataclass for IMU data. This includes fields for measurements from both MicroStrain and MPU9250 units.
- property accelerometer¶
- property gyroscope¶
- property magnetometer¶
- property quaternion¶
- property ef_quaternion¶
- property euler¶
- property rot_matrix¶
- property ref_rot_matrix¶