Paparazzi UAS  v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
imu.h File Reference

Inertial Measurement Unit interface. More...

#include "math/pprz_algebra_int.h"
#include "math/pprz_algebra_float.h"
#include "math/pprz_orientation_conversion.h"
#include "filters/low_pass_filter.h"
#include "generated/airframe.h"
+ Include dependency graph for imu.h:

Go to the source code of this file.

Data Structures

struct  imu_calib_t
 
struct  imu_gyro_t
 
struct  imu_accel_t
 
struct  imu_mag_t
 
struct  Imu
 abstract IMU interface providing fixed point interface
More...
 

Macros

#define IMU_MAX_SENSORS   4
 

Functions

void imu_init (void)
 External functions. More...
 
void imu_set_defaults_gyro (uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Rates *neutral, const struct Int32Rates *scale)
 Set the defaults for a gyro sensor WARNING: Should be called before sensor is publishing messages to ensure correct values. More...
 
void imu_set_defaults_accel (uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale)
 Set the defaults for a accel sensor WARNING: Should be called before sensor is publishing messages to ensure correct values. More...
 
void imu_set_defaults_mag (uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale)
 Set the defaults for a mag sensor WARNING: Should be called before sensor is publishing messages to ensure correct values. More...
 
struct imu_gyro_timu_get_gyro (uint8_t sender_id, bool create)
 Find or create the gyro in the imu structure. More...
 
struct imu_accel_timu_get_accel (uint8_t sender_id, bool create)
 Find or create the accel in the imu structure. More...
 
struct imu_mag_timu_get_mag (uint8_t sender_id, bool create)
 Find or create the mag in the imu structure. More...
 
void imu_SetBodyToImuPhi (float phi)
 
void imu_SetBodyToImuTheta (float theta)
 
void imu_SetBodyToImuPsi (float psi)
 
void imu_SetBodyToImuCurrent (float set)
 
void imu_ResetBodyToImu (float reset)
 

Variables

struct Imu imu
 global IMU state More...
 

Detailed Description

Inertial Measurement Unit interface.

Definition in file imu.h.


Data Structure Documentation

◆ imu_calib_t

struct imu_calib_t

Definition at line 41 of file imu.h.

Data Fields
bool current: 1 Current calibrated.
bool filter: 1 Enable the lowpass filter.
bool neutral: 1 Neutral values calibrated.
bool rotation: 1 Rotation calibrated.
bool scale: 1 Scale calibrated.

◆ imu_gyro_t

struct imu_gyro_t

Definition at line 49 of file imu.h.

+ Collaboration diagram for imu_gyro_t:
Data Fields
uint8_t abi_id ABI sensor ID.
struct Int32RMat body_to_sensor Rotation from body to sensor frame (body to imu combined with imu to sensor)
struct imu_calib_t calibrated Calibration bitmask.
Butterworth2LowPass filter[3] Lowpass filter optional.
float filter_freq Filter frequency.
float filter_sample_freq Lowpass filter sample frequency (Hz)
uint32_t last_stamp Last measurement timestamp for integration.
struct Int32Rates neutral Neutral values, compensation on unscaled->scaled.
struct Int32Rates scale[2] Scaling, first is numerator and second denominator.
struct Int32Rates scaled Last scaled values in body frame.
float temperature Temperature in degrees celcius.
struct Int32Rates unscaled Last unscaled values in sensor frame.

◆ imu_accel_t

struct imu_accel_t

Definition at line 64 of file imu.h.

+ Collaboration diagram for imu_accel_t:
Data Fields
uint8_t abi_id ABI sensor ID.
struct Int32RMat body_to_sensor Rotation from body to sensor frame (body to imu combined with imu to sensor)
struct imu_calib_t calibrated Calibration bitmask.
Butterworth2LowPass filter[3] Lowpass filter optional.
float filter_freq Lowpass filter frequency (Hz)
float filter_sample_freq Lowpass filter sample frequency (Hz)
uint32_t last_stamp Last measurement timestamp for integration.
struct Int32Vect3 neutral Neutral values, compensation on unscaled->scaled.
struct Int32Vect3 scale[2] Scaling, first is numerator and second denominator.
struct Int32Vect3 scaled Last scaled values in body frame.
float temperature Temperature in degrees celcius.
struct Int32Vect3 unscaled Last unscaled values in sensor frame.

◆ imu_mag_t

struct imu_mag_t

Definition at line 79 of file imu.h.

+ Collaboration diagram for imu_mag_t:
Data Fields
uint8_t abi_id ABI sensor ID.
struct Int32RMat body_to_sensor Rotation from body to sensor frame (body to imu combined with imu to sensor)
struct imu_calib_t calibrated Calibration bitmask.
struct FloatVect3 current_scale Current scaling multiplying.
struct Int32Vect3 neutral Neutral values, compensation on unscaled->scaled.
struct Int32Vect3 scale[2] Scaling, first is numerator and second denominator.
struct Int32Vect3 scaled Last scaled values in body frame.
struct Int32Vect3 unscaled Last unscaled values in sensor frame.

◆ Imu

struct Imu

abstract IMU interface providing fixed point interface

Definition at line 92 of file imu.h.

+ Collaboration diagram for Imu:
Data Fields
uint8_t accel_abi_send_id Filter out and send only a specific ABI id in telemetry for the accelerometer.
struct imu_accel_t accels[IMU_MAX_SENSORS] The accelerometer sensors.
bool b2i_set_current flag for adjusting body_to_imu via settings.

if FALSE, reset to airframe values, if TRUE set current roll/pitch

struct OrientationReps body_to_imu Rotation from body to imu (all sensors) frame.
uint8_t gyro_abi_send_id Filter out and send only a specific ABI id in telemetry for the gyro.
struct imu_gyro_t gyros[IMU_MAX_SENSORS] The gyro sensors.
bool initialized Check if the IMU is initialized.
uint8_t mag_abi_send_id Filter out and send only a specific ABI id in telemetry for the magnetometer.
struct imu_mag_t mags[IMU_MAX_SENSORS] The magnetometer sensors.

Macro Definition Documentation

◆ IMU_MAX_SENSORS

#define IMU_MAX_SENSORS   4

Definition at line 38 of file imu.h.

Function Documentation

◆ imu_get_accel()

struct imu_accel_t* imu_get_accel ( uint8_t  sender_id,
bool  create 
)

Find or create the accel in the imu structure.

Parameters
sender_idThe ABI sender id to search for
createCreate a new index if not found
Returns
struct imu_accel_t* The accel structure if found/created else NULL

Definition at line 907 of file imu.c.

References ABI_BROADCAST, ABI_DISABLE, imu_accel_t::abi_id, Imu::accels, imu, and IMU_MAX_SENSORS.

Referenced by ahrs_aligner_run(), high_speed_logger_spi_link_periodic(), imu_accel_raw_cb(), imu_quality_assessment_periodic(), and imu_set_defaults_accel().

+ Here is the caller graph for this function:

◆ imu_get_gyro()

struct imu_gyro_t* imu_get_gyro ( uint8_t  sender_id,
bool  create 
)

Find or create the gyro in the imu structure.

Parameters
sender_idThe ABI sender id to search for
createCreate a new index if not found
Returns
struct imu_gyro_t* The gyro structure if found/created else NULL

Definition at line 884 of file imu.c.

References ABI_BROADCAST, ABI_DISABLE, imu_gyro_t::abi_id, Imu::gyros, imu, and IMU_MAX_SENSORS.

Referenced by ahrs_aligner_run(), high_speed_logger_spi_link_periodic(), imu_gyro_raw_cb(), imu_set_defaults_gyro(), and send_aligner().

+ Here is the caller graph for this function:

◆ imu_get_mag()

struct imu_mag_t* imu_get_mag ( uint8_t  sender_id,
bool  create 
)

Find or create the mag in the imu structure.

Parameters
sender_idThe ABI sender id to search for
createCreate a new index if not found
Returns
struct imu_mag_t* The mag structure if found/created else NULL

Definition at line 931 of file imu.c.

References ABI_BROADCAST, ABI_DISABLE, imu_mag_t::abi_id, imu, IMU_MAX_SENSORS, and Imu::mags.

Referenced by ahrs_aligner_run(), high_speed_logger_spi_link_periodic(), imu_mag_raw_cb(), and imu_set_defaults_mag().

+ Here is the caller graph for this function:

◆ imu_init()

void imu_init ( void  )

External functions.

Definition at line 429 of file imu.c.

References ABI_BROADCAST, ABI_DISABLE, imu_gyro_t::abi_id, imu_accel_t::abi_id, imu_mag_t::abi_id, Imu::accel_abi_send_id, Imu::accels, Imu::body_to_imu, imu_gyro_t::body_to_sensor, imu_accel_t::body_to_sensor, imu_mag_t::body_to_sensor, imu_gyro_t::calibrated, imu_accel_t::calibrated, imu_mag_t::calibrated, imu_calib_t::current, imu_mag_t::current_scale, DefaultPeriodic, imu_calib_t::filter, imu_gyro_t::filter, imu_accel_t::filter, imu_gyro_t::filter_freq, imu_accel_t::filter_freq, imu_gyro_t::filter_sample_freq, imu_accel_t::filter_sample_freq, Imu::gyro_abi_send_id, Imu::gyros, imu, IMU_ACCEL_ABI_SEND_ID, IMU_ACCEL_CALIB, imu_accel_raw_cb(), imu_accel_raw_ev, IMU_ACCEL_X_SIGN, IMU_ACCEL_Y_SIGN, IMU_ACCEL_Z_SIGN, IMU_BODY_TO_IMU_PHI, IMU_BODY_TO_IMU_PSI, IMU_BODY_TO_IMU_THETA, IMU_GYRO_ABI_SEND_ID, IMU_GYRO_CALIB, IMU_GYRO_P_SIGN, IMU_GYRO_Q_SIGN, IMU_GYRO_R_SIGN, imu_gyro_raw_cb(), imu_gyro_raw_ev, IMU_MAG_ABI_SEND_ID, IMU_MAG_CALIB, imu_mag_raw_cb(), imu_mag_raw_ev, IMU_MAG_X_SIGN, IMU_MAG_Y_SIGN, IMU_MAG_Z_SIGN, IMU_MAX_SENSORS, init_butterworth_2_low_pass(), Imu::initialized, int32_rmat_comp(), int32_rmat_identity(), INT_RATES_ZERO, INT_VECT3_ZERO, imu_gyro_t::last_stamp, imu_accel_t::last_stamp, Imu::mag_abi_send_id, mag_calib, Imu::mags, imu_calib_t::neutral, imu_gyro_t::neutral, imu_accel_t::neutral, imu_mag_t::neutral, orientationGetRMat_i(), orientationSetEulers_f(), RATES_ASSIGN, register_periodic_telemetry(), RMAT_COPY, imu_calib_t::rotation, imu_calib_t::scale, imu_gyro_t::scale, imu_accel_t::scale, imu_mag_t::scale, send_accel(), send_accel_raw(), send_accel_scaled(), send_gyro(), send_gyro_raw(), send_gyro_scaled(), send_mag(), send_mag_current(), send_mag_raw(), send_mag_scaled(), shell_add_entry(), and VECT3_ASSIGN.

+ Here is the call graph for this function:

◆ imu_ResetBodyToImu()

void imu_ResetBodyToImu ( float  reset)

◆ imu_set_defaults_accel()

void imu_set_defaults_accel ( uint8_t  abi_id,
const struct Int32RMat imu_to_sensor,
const struct Int32Vect3 neutral,
const struct Int32Vect3 scale 
)

Set the defaults for a accel sensor WARNING: Should be called before sensor is publishing messages to ensure correct values.

Parameters
abi_idThe ABI sender id to set the defaults for
imu_to_sensorImu to sensor rotation matrix
neutralNeutral values
scaleScale values, 0 index is multiply and 1 index is divide

Definition at line 610 of file imu.c.

References imu_accel_t::abi_id, Imu::body_to_imu, imu_accel_t::body_to_sensor, imu_accel_t::calibrated, imu, IMU_ACCEL_X_SIGN, IMU_ACCEL_Y_SIGN, IMU_ACCEL_Z_SIGN, imu_get_accel(), int32_rmat_comp(), imu_calib_t::neutral, imu_accel_t::neutral, orientationGetRMat_i(), RMAT_COPY, imu_calib_t::rotation, imu_accel_t::scale, scale, imu_calib_t::scale, VECT3_ASSIGN, and VECT3_COPY.

Referenced by imu_apogee_init(), imu_aspirin2_init(), imu_aspirin_i2c_init(), imu_aspirin_init(), imu_bebop_init(), imu_bmi088_init(), imu_cube_init(), imu_disco_init(), imu_mpu9250_init(), imu_mpu_hmc_init(), imu_mpu_i2c_init(), imu_mpu_spi_init(), imu_nps_init(), imu_pixhawk6x_init(), imu_px4_init(), imu_px4fmu_init(), invensense2_fix_config(), invensense3_fix_config(), navdata_init(), and sensors_hitl_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ imu_set_defaults_gyro()

void imu_set_defaults_gyro ( uint8_t  abi_id,
const struct Int32RMat imu_to_sensor,
const struct Int32Rates neutral,
const struct Int32Rates scale 
)

Set the defaults for a gyro sensor WARNING: Should be called before sensor is publishing messages to ensure correct values.

Parameters
abi_idThe ABI sender id to set the defaults for
imu_to_sensorImu to sensor rotation matrix
neutralNeutral values
scaleScale values, 0 index is multiply and 1 index is divide

Definition at line 580 of file imu.c.

References imu_gyro_t::abi_id, Imu::body_to_imu, imu_gyro_t::body_to_sensor, imu_gyro_t::calibrated, imu, imu_get_gyro(), IMU_GYRO_P_SIGN, IMU_GYRO_Q_SIGN, IMU_GYRO_R_SIGN, int32_rmat_comp(), imu_calib_t::neutral, imu_gyro_t::neutral, orientationGetRMat_i(), RATES_ASSIGN, RATES_COPY, RMAT_COPY, imu_calib_t::rotation, scale, imu_calib_t::scale, and imu_gyro_t::scale.

Referenced by imu_apogee_init(), imu_aspirin2_init(), imu_aspirin_i2c_init(), imu_aspirin_init(), imu_bebop_init(), imu_bmi088_init(), imu_cube_init(), imu_disco_init(), imu_mpu9250_init(), imu_mpu_hmc_init(), imu_mpu_i2c_init(), imu_mpu_spi_init(), imu_nps_init(), imu_pixhawk6x_init(), imu_px4_init(), imu_px4fmu_init(), invensense2_fix_config(), invensense3_fix_config(), navdata_init(), and sensors_hitl_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ imu_set_defaults_mag()

void imu_set_defaults_mag ( uint8_t  abi_id,
const struct Int32RMat imu_to_sensor,
const struct Int32Vect3 neutral,
const struct Int32Vect3 scale 
)

Set the defaults for a mag sensor WARNING: Should be called before sensor is publishing messages to ensure correct values.

Parameters
abi_idThe ABI sender id to set the defaults for
imu_to_sensorImu to sensor rotation matrix
neutralNeutral values
scaleScale values, 0 index is multiply and 1 index is divide

Definition at line 640 of file imu.c.

References imu_mag_t::abi_id, Imu::body_to_imu, imu_mag_t::body_to_sensor, imu_mag_t::calibrated, imu, imu_get_mag(), IMU_MAG_X_SIGN, IMU_MAG_Y_SIGN, IMU_MAG_Z_SIGN, int32_rmat_comp(), imu_calib_t::neutral, imu_mag_t::neutral, orientationGetRMat_i(), RMAT_COPY, imu_calib_t::rotation, imu_mag_t::scale, scale, imu_calib_t::scale, VECT3_ASSIGN, and VECT3_COPY.

Referenced by imu_nps_init(), mag_ist8310_module_init(), mag_lis3mdl_module_init(), navdata_init(), and sensors_hitl_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ imu_SetBodyToImuCurrent()

◆ imu_SetBodyToImuPhi()

void imu_SetBodyToImuPhi ( float  phi)

Definition at line 982 of file imu.c.

References Imu::body_to_imu, imu, imu_set_body_to_imu_eulers(), orientationGetEulers_f(), and FloatEulers::phi.

+ Here is the call graph for this function:

◆ imu_SetBodyToImuPsi()

void imu_SetBodyToImuPsi ( float  psi)

Definition at line 998 of file imu.c.

References Imu::body_to_imu, imu, imu_set_body_to_imu_eulers(), orientationGetEulers_f(), and FloatEulers::psi.

+ Here is the call graph for this function:

◆ imu_SetBodyToImuTheta()

void imu_SetBodyToImuTheta ( float  theta)

Definition at line 990 of file imu.c.

References Imu::body_to_imu, imu, imu_set_body_to_imu_eulers(), orientationGetEulers_f(), and FloatEulers::theta.

+ Here is the call graph for this function:

Variable Documentation

◆ imu