diff --git a/sw/airborne/boards/apogee/imu_apogee.c b/sw/airborne/boards/apogee/imu_apogee.c index d3e7856f79..50c44d49ef 100644 --- a/sw/airborne/boards/apogee/imu_apogee.c +++ b/sw/airborne/boards/apogee/imu_apogee.c @@ -56,14 +56,7 @@ PRINT_CONFIG_MSG("Gyro/Accel output rate is 100Hz") PRINT_CONFIG_VAR(APOGEE_SMPLRT_DIV) PRINT_CONFIG_VAR(APOGEE_LOWPASS_FILTER) -#ifndef APOGEE_GYRO_RANGE -#define APOGEE_GYRO_RANGE MPU60X0_GYRO_RANGE_1000 -#endif PRINT_CONFIG_VAR(APOGEE_GYRO_RANGE) - -#ifndef APOGEE_ACCEL_RANGE -#define APOGEE_ACCEL_RANGE MPU60X0_ACCEL_RANGE_8G -#endif PRINT_CONFIG_VAR(APOGEE_ACCEL_RANGE) #if APOGEE_USE_MPU9150 diff --git a/sw/airborne/boards/apogee/imu_apogee.h b/sw/airborne/boards/apogee/imu_apogee.h index 1fba408762..72f4f93090 100644 --- a/sw/airborne/boards/apogee/imu_apogee.h +++ b/sw/airborne/boards/apogee/imu_apogee.h @@ -51,22 +51,24 @@ #define IMU_ACCEL_Z_SIGN 1 #endif -/** default gyro sensitivy and neutral from the datasheet - * MPU with 1000 deg/s has 32.8 LSB/(deg/s) - * sens = 1/32.8 * pi/180 * 2^INT32_RATE_FRAC - * sens = 1/32.8 * pi/180 * 4096 = 2.17953 - I*/ +#ifndef APOGEE_GYRO_RANGE +#define APOGEE_GYRO_RANGE MPU60X0_GYRO_RANGE_1000 +#endif +#ifndef APOGEE_ACCEL_RANGE +#define APOGEE_ACCEL_RANGE MPU60X0_ACCEL_RANGE_8G +#endif + +// Set default sensitivity based on range if needed #if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS -// FIXME -#define IMU_GYRO_P_SENS 2.17953 -#define IMU_GYRO_P_SENS_NUM 18271 -#define IMU_GYRO_P_SENS_DEN 8383 -#define IMU_GYRO_Q_SENS 2.17953 -#define IMU_GYRO_Q_SENS_NUM 18271 -#define IMU_GYRO_Q_SENS_DEN 8383 -#define IMU_GYRO_R_SENS 2.17953 -#define IMU_GYRO_R_SENS_NUM 18271 -#define IMU_GYRO_R_SENS_DEN 8383 +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[APOGEE_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[APOGEE_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[APOGEE_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[APOGEE_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[APOGEE_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[APOGEE_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[APOGEE_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[APOGEE_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[APOGEE_GYRO_RANGE][1] #endif #if !defined IMU_GYRO_P_NEUTRAL & !defined IMU_GYRO_Q_NEUTRAL & !defined IMU_GYRO_R_NEUTRAL #define IMU_GYRO_P_NEUTRAL 0 @@ -75,21 +77,17 @@ #endif -/** default accel sensitivy from the datasheet - * MPU with 8g has 4096 LSB/g - * sens = 9.81 [m/s^2] / 4096 [LSB/g] * 2^INT32_ACCEL_FRAC = 2.4525 - */ +// Set default sensitivity based on range if needed #if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS -// FIXME -#define IMU_ACCEL_X_SENS 2.4525 -#define IMU_ACCEL_X_SENS_NUM 981 -#define IMU_ACCEL_X_SENS_DEN 400 -#define IMU_ACCEL_Y_SENS 2.4525 -#define IMU_ACCEL_Y_SENS_NUM 981 -#define IMU_ACCEL_Y_SENS_DEN 400 -#define IMU_ACCEL_Z_SENS 2.4525 -#define IMU_ACCEL_Z_SENS_NUM 981 -#define IMU_ACCEL_Z_SENS_DEN 400 +#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[APOGEE_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[APOGEE_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[APOGEE_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[APOGEE_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[APOGEE_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[APOGEE_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[APOGEE_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[APOGEE_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[APOGEE_ACCEL_RANGE][1] #endif #if !defined IMU_ACCEL_X_NEUTRAL & !defined IMU_ACCEL_Y_NEUTRAL & !defined IMU_ACCEL_Z_NEUTRAL #define IMU_ACCEL_X_NEUTRAL 0 diff --git a/sw/airborne/boards/krooz/imu_krooz.c b/sw/airborne/boards/krooz/imu_krooz.c index 773d1c7a9b..21dc0a5c81 100644 --- a/sw/airborne/boards/krooz/imu_krooz.c +++ b/sw/airborne/boards/krooz/imu_krooz.c @@ -48,14 +48,7 @@ PRINT_CONFIG_VAR(KROOZ_SMPLRT_DIV) PRINT_CONFIG_VAR(KROOZ_LOWPASS_FILTER) -#ifndef KROOZ_GYRO_RANGE -#define KROOZ_GYRO_RANGE MPU60X0_GYRO_RANGE_250 -#endif PRINT_CONFIG_VAR(KROOZ_GYRO_RANGE) - -#ifndef KROOZ_ACCEL_RANGE -#define KROOZ_ACCEL_RANGE MPU60X0_ACCEL_RANGE_2G -#endif PRINT_CONFIG_VAR(KROOZ_ACCEL_RANGE) struct ImuKrooz imu_krooz; diff --git a/sw/airborne/boards/krooz/imu_krooz.h b/sw/airborne/boards/krooz/imu_krooz.h index d6392b5d2d..3af518dd2e 100644 --- a/sw/airborne/boards/krooz/imu_krooz.h +++ b/sw/airborne/boards/krooz/imu_krooz.h @@ -37,69 +37,42 @@ #include "peripherals/mpu60x0_i2c.h" #include "peripherals/hmc58xx.h" -// Default configuration -#if !defined IMU_GYRO_P_SIGN & !defined IMU_GYRO_Q_SIGN & !defined IMU_GYRO_R_SIGN -#define IMU_GYRO_P_SIGN 1 -#define IMU_GYRO_Q_SIGN 1 -#define IMU_GYRO_R_SIGN 1 -#endif -#if !defined IMU_ACCEL_X_SIGN & !defined IMU_ACCEL_Y_SIGN & !defined IMU_ACCEL_Z_SIGN -#define IMU_ACCEL_X_SIGN 1 -#define IMU_ACCEL_Y_SIGN 1 -#define IMU_ACCEL_Z_SIGN 1 -#endif -#if !defined IMU_MAG_X_SIGN & !defined IMU_MAG_Y_SIGN & !defined IMU_MAG_Z_SIGN -#define IMU_MAG_X_SIGN 1 -#define IMU_MAG_Y_SIGN 1 -#define IMU_MAG_Z_SIGN 1 +#ifndef KROOZ_GYRO_RANGE +#define KROOZ_GYRO_RANGE MPU60X0_GYRO_RANGE_250 #endif -/** default gyro sensitivy and neutral from the datasheet - * MPU with 250 deg/s has 131.072 LSB/(deg/s) - * sens = 1/131.072 * pi/180 * 2^INT32_RATE_FRAC - * sens = 1/131.072 * pi/180 * 4096 = 0.5454 - I*/ +#ifndef KROOZ_ACCEL_RANGE +#define KROOZ_ACCEL_RANGE MPU60X0_ACCEL_RANGE_2G +#endif + + +// Set default sensitivity based on range if needed #if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS -// FIXME -#define IMU_GYRO_P_SENS 0.5454 -#define IMU_GYRO_P_SENS_NUM 2727 -#define IMU_GYRO_P_SENS_DEN 5000 -#define IMU_GYRO_Q_SENS 0.5454 -#define IMU_GYRO_Q_SENS_NUM 2727 -#define IMU_GYRO_Q_SENS_DEN 5000 -#define IMU_GYRO_R_SENS 0.5454 -#define IMU_GYRO_R_SENS_NUM 2727 -#define IMU_GYRO_R_SENS_DEN 5000 -#endif -#if !defined IMU_GYRO_P_NEUTRAL & !defined IMU_GYRO_Q_NEUTRAL & !defined IMU_GYRO_R_NEUTRAL -#define IMU_GYRO_P_NEUTRAL 0 -#define IMU_GYRO_Q_NEUTRAL 0 -#define IMU_GYRO_R_NEUTRAL 0 +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[KROOZ_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[KROOZ_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[KROOZ_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][1] #endif - -/** default accel sensitivy from the datasheet - * MPU with 2g has 16384 LSB/g - * sens = 9.81 [m/s^2] / 16384 [LSB/g] * 2^INT32_ACCEL_FRAC = 0.6131 - */ +// Set default sensitivity based on range if needed #if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS -// FIXME -#define IMU_ACCEL_X_SENS 0.6131 -#define IMU_ACCEL_X_SENS_NUM 6131 -#define IMU_ACCEL_X_SENS_DEN 10000 -#define IMU_ACCEL_Y_SENS 0.6131 -#define IMU_ACCEL_Y_SENS_NUM 6131 -#define IMU_ACCEL_Y_SENS_DEN 10000 -#define IMU_ACCEL_Z_SENS 0.6131 -#define IMU_ACCEL_Z_SENS_NUM 6131 -#define IMU_ACCEL_Z_SENS_DEN 10000 -#endif -#if !defined IMU_ACCEL_X_NEUTRAL & !defined IMU_ACCEL_Y_NEUTRAL & !defined IMU_ACCEL_Z_NEUTRAL -#define IMU_ACCEL_X_NEUTRAL 0 -#define IMU_ACCEL_Y_NEUTRAL 0 -#define IMU_ACCEL_Z_NEUTRAL 0 +#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[KROOZ_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[KROOZ_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[KROOZ_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[KROOZ_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[KROOZ_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[KROOZ_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[KROOZ_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[KROOZ_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[KROOZ_ACCEL_RANGE][1] #endif + #ifndef IMU_KROOZ_ACCEL_AVG_FILTER #define IMU_KROOZ_ACCEL_AVG_FILTER 15 #endif diff --git a/sw/airborne/boards/krooz/imu_krooz_memsic.c b/sw/airborne/boards/krooz/imu_krooz_memsic.c index 6ea010decb..b6f002a89e 100644 --- a/sw/airborne/boards/krooz/imu_krooz_memsic.c +++ b/sw/airborne/boards/krooz/imu_krooz_memsic.c @@ -45,9 +45,6 @@ PRINT_CONFIG_VAR(KROOZ_SMPLRT_DIV) PRINT_CONFIG_VAR(KROOZ_LOWPASS_FILTER) -#ifndef KROOZ_GYRO_RANGE -#define KROOZ_GYRO_RANGE MPU60X0_GYRO_RANGE_250 -#endif PRINT_CONFIG_VAR(KROOZ_GYRO_RANGE) #ifndef KROOZ_ACCEL_RANGE diff --git a/sw/airborne/boards/krooz/imu_krooz_memsic.h b/sw/airborne/boards/krooz/imu_krooz_memsic.h index 0ebdced215..e8ab964fe8 100644 --- a/sw/airborne/boards/krooz/imu_krooz_memsic.h +++ b/sw/airborne/boards/krooz/imu_krooz_memsic.h @@ -40,44 +40,21 @@ #include "peripherals/hmc58xx.h" #include "mcu_periph/spi.h" -// Default configuration -#if !defined IMU_GYRO_P_SIGN & !defined IMU_GYRO_Q_SIGN & !defined IMU_GYRO_R_SIGN -#define IMU_GYRO_P_SIGN 1 -#define IMU_GYRO_Q_SIGN 1 -#define IMU_GYRO_R_SIGN 1 -#endif -#if !defined IMU_ACCEL_X_SIGN & !defined IMU_ACCEL_Y_SIGN & !defined IMU_ACCEL_Z_SIGN -#define IMU_ACCEL_X_SIGN 1 -#define IMU_ACCEL_Y_SIGN 1 -#define IMU_ACCEL_Z_SIGN 1 -#endif -#if !defined IMU_MAG_X_SIGN & !defined IMU_MAG_Y_SIGN & !defined IMU_MAG_Z_SIGN -#define IMU_MAG_X_SIGN 1 -#define IMU_MAG_Y_SIGN 1 -#define IMU_MAG_Z_SIGN 1 +#ifndef KROOZ_GYRO_RANGE +#define KROOZ_GYRO_RANGE MPU60X0_GYRO_RANGE_250 #endif -/** default gyro sensitivy and neutral from the datasheet - * MPU with 250 deg/s has 131.072 LSB/(deg/s) - * sens = 1/131.072 * pi/180 * 2^INT32_RATE_FRAC - * sens = 1/131.072 * pi/180 * 4096 = 0.5454 - I*/ +// Set default sensitivity based on range if needed #if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS -// FIXME -#define IMU_GYRO_P_SENS 0.5454 -#define IMU_GYRO_P_SENS_NUM 2727 -#define IMU_GYRO_P_SENS_DEN 5000 -#define IMU_GYRO_Q_SENS 0.5454 -#define IMU_GYRO_Q_SENS_NUM 2727 -#define IMU_GYRO_Q_SENS_DEN 5000 -#define IMU_GYRO_R_SENS 0.5454 -#define IMU_GYRO_R_SENS_NUM 2727 -#define IMU_GYRO_R_SENS_DEN 5000 -#endif -#if !defined IMU_GYRO_P_NEUTRAL & !defined IMU_GYRO_Q_NEUTRAL & !defined IMU_GYRO_R_NEUTRAL -#define IMU_GYRO_P_NEUTRAL 0 -#define IMU_GYRO_Q_NEUTRAL 0 -#define IMU_GYRO_R_NEUTRAL 0 +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[KROOZ_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[KROOZ_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[KROOZ_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[KROOZ_GYRO_RANGE][1] #endif diff --git a/sw/airborne/peripherals/mpu60x0.c b/sw/airborne/peripherals/mpu60x0.c index 9c7098b44a..5eb535fa2b 100644 --- a/sw/airborne/peripherals/mpu60x0.c +++ b/sw/airborne/peripherals/mpu60x0.c @@ -24,11 +24,39 @@ * * MPU-60X0 driver common functions (I2C and SPI). * - * Still needs the either the I2C or SPI specific implementation. + * Still needs the either I2C or SPI specific implementation. */ #include "peripherals/mpu60x0.h" +const float MPU60X0_GYRO_SENS[4] = { + MPU60X0_GYRO_SENS_250, + MPU60X0_GYRO_SENS_500, + MPU60X0_GYRO_SENS_1000, + MPU60X0_GYRO_SENS_2000 +}; + +const int32_t MPU60X0_GYRO_SENS_FRAC[4][2] = { + { MPU60X0_GYRO_SENS_250_NUM, MPU60X0_GYRO_SENS_250_DEN }, + { MPU60X0_GYRO_SENS_500_NUM, MPU60X0_GYRO_SENS_500_DEN }, + { MPU60X0_GYRO_SENS_1000_NUM, MPU60X0_GYRO_SENS_1000_DEN }, + { MPU60X0_GYRO_SENS_2000_NUM, MPU60X0_GYRO_SENS_2000_DEN } +}; + +const float MPU60X0_ACCEL_SENS[4] = { + MPU60X0_ACCEL_SENS_2G, + MPU60X0_ACCEL_SENS_4G, + MPU60X0_ACCEL_SENS_8G, + MPU60X0_ACCEL_SENS_16G +}; + +const int32_t MPU60X0_ACCEL_SENS_FRAC[4][2] = { + { MPU60X0_ACCEL_SENS_2G_NUM, MPU60X0_ACCEL_SENS_2G_DEN }, + { MPU60X0_ACCEL_SENS_4G_NUM, MPU60X0_ACCEL_SENS_4G_DEN }, + { MPU60X0_ACCEL_SENS_8G_NUM, MPU60X0_ACCEL_SENS_8G_DEN }, + { MPU60X0_ACCEL_SENS_16G_NUM, MPU60X0_ACCEL_SENS_16G_DEN } +}; + void mpu60x0_set_default_config(struct Mpu60x0Config *c) { c->clk_sel = MPU60X0_DEFAULT_CLK_SEL; diff --git a/sw/airborne/peripherals/mpu60x0.h b/sw/airborne/peripherals/mpu60x0.h index 4293cb6b26..3c88d1c3ed 100644 --- a/sw/airborne/peripherals/mpu60x0.h +++ b/sw/airborne/peripherals/mpu60x0.h @@ -51,6 +51,52 @@ #define MPU60X0_I2C_NB_SLAVES 5 #endif +/** default gyro sensitivy from the datasheet + * sens = 1/ [LSB/(deg/s)] * pi/180 * 2^INT32_RATE_FRAC + * ex: MPU with 1000 deg/s has 32.8 LSB/(deg/s) + * sens = 1/32.8 * pi/180 * 4096 = 2.17953 + */ +#define MPU60X0_GYRO_SENS_250 0.544883 +#define MPU60X0_GYRO_SENS_250_NUM 19327 +#define MPU60X0_GYRO_SENS_250_DEN 35470 +#define MPU60X0_GYRO_SENS_500 1.08977 +#define MPU60X0_GYRO_SENS_500_NUM 57663 +#define MPU60X0_GYRO_SENS_500_DEN 52913 +#define MPU60X0_GYRO_SENS_1000 2.17953 +#define MPU60X0_GYRO_SENS_1000_NUM 18271 +#define MPU60X0_GYRO_SENS_1000_DEN 8383 +#define MPU60X0_GYRO_SENS_2000 4.35906 +#define MPU60X0_GYRO_SENS_2000_NUM 36542 +#define MPU60X0_GYRO_SENS_2000_DEN 8383 + +// Get default sensitivity from a table +extern const float MPU60X0_GYRO_SENS[4]; +// Get default sensitivity numerator and denominator from a table +extern const int32_t MPU60X0_GYRO_SENS_FRAC[4][2]; + +/** default accel sensitivy from the datasheet + * sens = 9.81 [m/s^2] / [LSB/g] * 2^INT32_ACCEL_FRAC + * ex: MPU with 8g has 4096 LSB/g + * sens = 9.81 [m/s^2] / 4096 [LSB/g] * 2^INT32_ACCEL_FRAC = 2.4525 + */ +#define MPU60X0_ACCEL_SENS_2G 0.613125 +#define MPU60X0_ACCEL_SENS_2G_NUM 981 +#define MPU60X0_ACCEL_SENS_2G_DEN 1600 +#define MPU60X0_ACCEL_SENS_4G 1.22625 +#define MPU60X0_ACCEL_SENS_4G_NUM 981 +#define MPU60X0_ACCEL_SENS_4G_DEN 800 +#define MPU60X0_ACCEL_SENS_8G 2.4525 +#define MPU60X0_ACCEL_SENS_8G_NUM 981 +#define MPU60X0_ACCEL_SENS_8G_DEN 400 +#define MPU60X0_ACCEL_SENS_16G 4.905 +#define MPU60X0_ACCEL_SENS_16G_NUM 981 +#define MPU60X0_ACCEL_SENS_16G_DEN 200 + +// Get default sensitivity from a table +extern const float MPU60X0_ACCEL_SENS[4]; +// Get default sensitivity numerator and denominator from a table +extern const int32_t MPU60X0_ACCEL_SENS_FRAC[4][2]; + enum Mpu60x0ConfStatus { MPU60X0_CONF_UNINIT, MPU60X0_CONF_RESET, diff --git a/sw/airborne/peripherals/mpu9250.c b/sw/airborne/peripherals/mpu9250.c index 8adac4a30a..c79ea9e224 100644 --- a/sw/airborne/peripherals/mpu9250.c +++ b/sw/airborne/peripherals/mpu9250.c @@ -24,11 +24,39 @@ * * MPU-9250 driver common functions (I2C and SPI). * - * Still needs the either the I2C or SPI specific implementation. + * Still needs the either I2C or SPI specific implementation. */ #include "peripherals/mpu9250.h" +const float MPU9250_GYRO_SENS[4] = { + MPU9250_GYRO_SENS_250, + MPU9250_GYRO_SENS_500, + MPU9250_GYRO_SENS_1000, + MPU9250_GYRO_SENS_2000 +}; + +const int32_t MPU9250_GYRO_SENS_FRAC[4][2] = { + { MPU9250_GYRO_SENS_250_NUM, MPU9250_GYRO_SENS_250_DEN }, + { MPU9250_GYRO_SENS_500_NUM, MPU9250_GYRO_SENS_500_DEN }, + { MPU9250_GYRO_SENS_1000_NUM, MPU9250_GYRO_SENS_1000_DEN }, + { MPU9250_GYRO_SENS_2000_NUM, MPU9250_GYRO_SENS_2000_DEN } +}; + +const float MPU9250_ACCEL_SENS[4] = { + MPU9250_ACCEL_SENS_2G, + MPU9250_ACCEL_SENS_4G, + MPU9250_ACCEL_SENS_8G, + MPU9250_ACCEL_SENS_16G +}; + +const int32_t MPU9250_ACCEL_SENS_FRAC[4][2] = { + { MPU9250_ACCEL_SENS_2G_NUM, MPU9250_ACCEL_SENS_2G_DEN }, + { MPU9250_ACCEL_SENS_4G_NUM, MPU9250_ACCEL_SENS_4G_DEN }, + { MPU9250_ACCEL_SENS_8G_NUM, MPU9250_ACCEL_SENS_8G_DEN }, + { MPU9250_ACCEL_SENS_16G_NUM, MPU9250_ACCEL_SENS_16G_DEN } +}; + void mpu9250_set_default_config(struct Mpu9250Config *c) { c->clk_sel = MPU9250_DEFAULT_CLK_SEL; diff --git a/sw/airborne/peripherals/mpu9250.h b/sw/airborne/peripherals/mpu9250.h index 2ad631df5c..db19d9d061 100644 --- a/sw/airborne/peripherals/mpu9250.h +++ b/sw/airborne/peripherals/mpu9250.h @@ -52,6 +52,52 @@ #define MPU9250_I2C_NB_SLAVES 5 #endif +/** default gyro sensitivy from the datasheet + * sens = 1/ [LSB/(deg/s)] * pi/180 * 2^INT32_RATE_FRAC + * ex: MPU with 1000 deg/s has 32.8 LSB/(deg/s) + * sens = 1/32.8 * pi/180 * 4096 = 2.17953 + */ +#define MPU9250_GYRO_SENS_250 0.544883 +#define MPU9250_GYRO_SENS_250_NUM 19327 +#define MPU9250_GYRO_SENS_250_DEN 35470 +#define MPU9250_GYRO_SENS_500 1.08977 +#define MPU9250_GYRO_SENS_500_NUM 57663 +#define MPU9250_GYRO_SENS_500_DEN 52913 +#define MPU9250_GYRO_SENS_1000 2.17953 +#define MPU9250_GYRO_SENS_1000_NUM 18271 +#define MPU9250_GYRO_SENS_1000_DEN 8383 +#define MPU9250_GYRO_SENS_2000 4.35906 +#define MPU9250_GYRO_SENS_2000_NUM 36542 +#define MPU9250_GYRO_SENS_2000_DEN 8383 + +// Get default sensitivity from a table +extern const float MPU9250_GYRO_SENS[4]; +// Get default sensitivity numerator and denominator from a table +extern const int32_t MPU9250_GYRO_SENS_FRAC[4][2]; + +/** default accel sensitivy from the datasheet + * sens = 9.81 [m/s^2] / [LSB/g] * 2^INT32_ACCEL_FRAC + * ex: MPU with 8g has 4096 LSB/g + * sens = 9.81 [m/s^2] / 4096 [LSB/g] * 2^INT32_ACCEL_FRAC = 2.4525 + */ +#define MPU9250_ACCEL_SENS_2G 0.613125 +#define MPU9250_ACCEL_SENS_2G_NUM 981 +#define MPU9250_ACCEL_SENS_2G_DEN 1600 +#define MPU9250_ACCEL_SENS_4G 1.22625 +#define MPU9250_ACCEL_SENS_4G_NUM 981 +#define MPU9250_ACCEL_SENS_4G_DEN 800 +#define MPU9250_ACCEL_SENS_8G 2.4525 +#define MPU9250_ACCEL_SENS_8G_NUM 981 +#define MPU9250_ACCEL_SENS_8G_DEN 400 +#define MPU9250_ACCEL_SENS_16G 4.905 +#define MPU9250_ACCEL_SENS_16G_NUM 981 +#define MPU9250_ACCEL_SENS_16G_DEN 200 + +// Get default sensitivity from a table +extern const float MPU9250_ACCEL_SENS[4]; +// Get default sensitivity numerator and denominator from a table +extern const int32_t MPU9250_ACCEL_SENS_FRAC[4][2]; + enum Mpu9250ConfStatus { MPU9250_CONF_UNINIT, MPU9250_CONF_RESET, diff --git a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c index 354ff3bea6..a01e7d9eb6 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c +++ b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c @@ -64,14 +64,7 @@ PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling") PRINT_CONFIG_VAR(ASPIRIN_2_LOWPASS_FILTER) PRINT_CONFIG_VAR(ASPIRIN_2_SMPLRT_DIV) -#ifndef ASPIRIN_2_GYRO_RANGE -#define ASPIRIN_2_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 -#endif PRINT_CONFIG_VAR(ASPIRIN_2_GYRO_RANGE) - -#ifndef ASPIRIN_2_ACCEL_RANGE -#define ASPIRIN_2_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G -#endif PRINT_CONFIG_VAR(ASPIRIN_2_ACCEL_RANGE) diff --git a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.h b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.h index be9e9fcdb3..b3b0c0729a 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.h +++ b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.h @@ -31,10 +31,42 @@ #include "generated/airframe.h" #include "subsystems/imu.h" -/* default sensitivitiy */ -#include "subsystems/imu/imu_mpu60x0_defaults.h" #include "peripherals/mpu60x0_spi.h" +#ifndef ASPIRIN_2_GYRO_RANGE +#define ASPIRIN_2_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 +#endif + +#ifndef ASPIRIN_2_ACCEL_RANGE +#define ASPIRIN_2_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[ASPIRIN_2_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[ASPIRIN_2_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[ASPIRIN_2_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[ASPIRIN_2_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[ASPIRIN_2_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[ASPIRIN_2_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[ASPIRIN_2_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[ASPIRIN_2_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[ASPIRIN_2_GYRO_RANGE][1] +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS +#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[ASPIRIN_2_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[ASPIRIN_2_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[ASPIRIN_2_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[ASPIRIN_2_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[ASPIRIN_2_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[ASPIRIN_2_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[ASPIRIN_2_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[ASPIRIN_2_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[ASPIRIN_2_ACCEL_RANGE][1] +#endif + struct ImuAspirin2Spi { struct Mpu60x0_Spi mpu; diff --git a/sw/airborne/subsystems/imu/imu_bebop.c b/sw/airborne/subsystems/imu/imu_bebop.c index ee7ad825ce..3d357176ae 100644 --- a/sw/airborne/subsystems/imu/imu_bebop.c +++ b/sw/airborne/subsystems/imu/imu_bebop.c @@ -60,14 +60,7 @@ PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling") PRINT_CONFIG_VAR(BEBOP_SMPLRT_DIV) PRINT_CONFIG_VAR(BEBOP_LOWPASS_FILTER) -#ifndef BEBOP_GYRO_RANGE -#define BEBOP_GYRO_RANGE MPU60X0_GYRO_RANGE_1000 -#endif PRINT_CONFIG_VAR(BEBOP_GYRO_RANGE) - -#ifndef BEBOP_ACCEL_RANGE -#define BEBOP_ACCEL_RANGE MPU60X0_ACCEL_RANGE_8G -#endif PRINT_CONFIG_VAR(BEBOP_ACCEL_RANGE) struct OrientationReps imu_to_mag_bebop; ///< IMU to magneto rotation diff --git a/sw/airborne/subsystems/imu/imu_bebop.h b/sw/airborne/subsystems/imu/imu_bebop.h index df11ae6114..669041437c 100644 --- a/sw/airborne/subsystems/imu/imu_bebop.h +++ b/sw/airborne/subsystems/imu/imu_bebop.h @@ -34,41 +34,41 @@ #include "peripherals/ak8963.h" #include "peripherals/mpu60x0_i2c.h" -/** default gyro sensitivy and neutral from the datasheet - * MPU with 1000 deg/s has 32.8 LSB/(deg/s) - * sens = 1/32.8 * pi/180 * 2^INT32_RATE_FRAC - * sens = 1/32.8 * pi/180 * 4096 = 2.17953 - */ -#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS -// FIXME -#define IMU_GYRO_P_SENS 2.17953 -#define IMU_GYRO_P_SENS_NUM 18271 -#define IMU_GYRO_P_SENS_DEN 8383 -#define IMU_GYRO_Q_SENS 2.17953 -#define IMU_GYRO_Q_SENS_NUM 18271 -#define IMU_GYRO_Q_SENS_DEN 8383 -#define IMU_GYRO_R_SENS 2.17953 -#define IMU_GYRO_R_SENS_NUM 18271 -#define IMU_GYRO_R_SENS_DEN 8383 +#ifndef BEBOP_GYRO_RANGE +#define BEBOP_GYRO_RANGE MPU60X0_GYRO_RANGE_1000 #endif -/** default accel sensitivy from the datasheet - * MPU with 8g has 4096 LSB/g - * sens = 9.81 [m/s^2] / 4096 [LSB/g] * 2^INT32_ACCEL_FRAC = 2.4525 - */ -#if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS -// FIXME -#define IMU_ACCEL_X_SENS 2.4525 -#define IMU_ACCEL_X_SENS_NUM 981 -#define IMU_ACCEL_X_SENS_DEN 400 -#define IMU_ACCEL_Y_SENS 2.4525 -#define IMU_ACCEL_Y_SENS_NUM 981 -#define IMU_ACCEL_Y_SENS_DEN 400 -#define IMU_ACCEL_Z_SENS 2.4525 -#define IMU_ACCEL_Z_SENS_NUM 981 -#define IMU_ACCEL_Z_SENS_DEN 400 +#ifndef BEBOP_ACCEL_RANGE +#define BEBOP_ACCEL_RANGE MPU60X0_ACCEL_RANGE_8G #endif +// Set default sensitivity based on range if needed +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[BEBOP_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[BEBOP_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[BEBOP_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[BEBOP_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[BEBOP_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[BEBOP_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[BEBOP_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[BEBOP_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[BEBOP_GYRO_RANGE][1] +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS +#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[BEBOP_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[BEBOP_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[BEBOP_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[BEBOP_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[BEBOP_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[BEBOP_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[BEBOP_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[BEBOP_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[BEBOP_ACCEL_RANGE][1] +#endif + + /** Everything that is in the bebop IMU */ struct ImuBebop { struct Mpu60x0_I2c mpu; ///< The MPU gyro/accel device diff --git a/sw/airborne/subsystems/imu/imu_disco.c b/sw/airborne/subsystems/imu/imu_disco.c index c5c56e03fe..bd2bb6bc98 100644 --- a/sw/airborne/subsystems/imu/imu_disco.c +++ b/sw/airborne/subsystems/imu/imu_disco.c @@ -49,14 +49,7 @@ PRINT_CONFIG_MSG("Gyro/Accel output rate is 100Hz at 1kHz internal sampling") PRINT_CONFIG_VAR(DISCO_SMPLRT_DIV) PRINT_CONFIG_VAR(DISCO_LOWPASS_FILTER) -#ifndef DISCO_GYRO_RANGE -#define DISCO_GYRO_RANGE MPU60X0_GYRO_RANGE_1000 -#endif PRINT_CONFIG_VAR(DISCO_GYRO_RANGE) - -#ifndef DISCO_ACCEL_RANGE -#define DISCO_ACCEL_RANGE MPU60X0_ACCEL_RANGE_8G -#endif PRINT_CONFIG_VAR(DISCO_ACCEL_RANGE) /** Disco IMU data */ diff --git a/sw/airborne/subsystems/imu/imu_disco.h b/sw/airborne/subsystems/imu/imu_disco.h index ed4bcf600e..a1710072f5 100644 --- a/sw/airborne/subsystems/imu/imu_disco.h +++ b/sw/airborne/subsystems/imu/imu_disco.h @@ -34,39 +34,38 @@ #include "peripherals/ak8963.h" #include "peripherals/mpu60x0_i2c.h" -/** default gyro sensitivy and neutral from the datasheet - * MPU with 1000 deg/s has 32.8 LSB/(deg/s) - * sens = 1/32.8 * pi/180 * 2^INT32_RATE_FRAC - * sens = 1/32.8 * pi/180 * 4096 = 2.17953 - */ -#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS -// FIXME -#define IMU_GYRO_P_SENS 2.17953 -#define IMU_GYRO_P_SENS_NUM 18271 -#define IMU_GYRO_P_SENS_DEN 8383 -#define IMU_GYRO_Q_SENS 2.17953 -#define IMU_GYRO_Q_SENS_NUM 18271 -#define IMU_GYRO_Q_SENS_DEN 8383 -#define IMU_GYRO_R_SENS 2.17953 -#define IMU_GYRO_R_SENS_NUM 18271 -#define IMU_GYRO_R_SENS_DEN 8383 +#ifndef DISCO_GYRO_RANGE +#define DISCO_GYRO_RANGE MPU60X0_GYRO_RANGE_1000 #endif -/** default accel sensitivy from the datasheet - * MPU with 8g has 4096 LSB/g - * sens = 9.81 [m/s^2] / 4096 [LSB/g] * 2^INT32_ACCEL_FRAC = 2.4525 - */ +#ifndef DISCO_ACCEL_RANGE +#define DISCO_ACCEL_RANGE MPU60X0_ACCEL_RANGE_8G +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[DISCO_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[DISCO_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[DISCO_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[DISCO_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[DISCO_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[DISCO_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[DISCO_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[DISCO_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[DISCO_GYRO_RANGE][1] +#endif + +// Set default sensitivity based on range if needed #if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS -// FIXME -#define IMU_ACCEL_X_SENS 2.4525 -#define IMU_ACCEL_X_SENS_NUM 981 -#define IMU_ACCEL_X_SENS_DEN 400 -#define IMU_ACCEL_Y_SENS 2.4525 -#define IMU_ACCEL_Y_SENS_NUM 981 -#define IMU_ACCEL_Y_SENS_DEN 400 -#define IMU_ACCEL_Z_SENS 2.4525 -#define IMU_ACCEL_Z_SENS_NUM 981 -#define IMU_ACCEL_Z_SENS_DEN 400 +#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[DISCO_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[DISCO_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[DISCO_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[DISCO_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[DISCO_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[DISCO_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[DISCO_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[DISCO_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[DISCO_ACCEL_RANGE][1] #endif /** Everything that is in the disco IMU */ diff --git a/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c b/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c index d5bb4af427..12d0b5d1c9 100644 --- a/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c +++ b/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c @@ -56,14 +56,7 @@ PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling") PRINT_CONFIG_VAR(DROTEK_2_SMPLRT_DIV) PRINT_CONFIG_VAR(DROTEK_2_LOWPASS_FILTER) -#ifndef DROTEK_2_GYRO_RANGE -#define DROTEK_2_GYRO_RANGE MPU60X0_GYRO_RANGE_1000 -#endif PRINT_CONFIG_VAR(DROTEK_2_GYRO_RANGE) - -#ifndef DROTEK_2_ACCEL_RANGE -#define DROTEK_2_ACCEL_RANGE MPU60X0_ACCEL_RANGE_8G -#endif PRINT_CONFIG_VAR(DROTEK_2_ACCEL_RANGE) #ifndef DROTEK_2_MPU_I2C_ADDR diff --git a/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.h b/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.h index a841bce12c..b5b0e4dac1 100644 --- a/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.h +++ b/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.h @@ -36,43 +36,42 @@ #include "peripherals/mpu60x0_i2c.h" #include "peripherals/hmc58xx.h" +#ifndef DROTEK_2_GYRO_RANGE +#define DROTEK_2_GYRO_RANGE MPU60X0_GYRO_RANGE_1000 +#endif -/** default gyro sensitivy and neutral from the datasheet - * MPU with 1000 deg/s has 32.8 LSB/(deg/s) - * sens = 1/32.8 * pi/180 * 2^INT32_RATE_FRAC - * sens = 1/32.8 * pi/180 * 4096 = 2.17953 - I*/ +#ifndef DROTEK_2_ACCEL_RANGE +#define DROTEK_2_ACCEL_RANGE MPU60X0_ACCEL_RANGE_8G +#endif + +// Set default sensitivity based on range if needed #if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS -// FIXME -#define IMU_GYRO_P_SENS 2.17953 -#define IMU_GYRO_P_SENS_NUM 18271 -#define IMU_GYRO_P_SENS_DEN 8383 -#define IMU_GYRO_Q_SENS 2.17953 -#define IMU_GYRO_Q_SENS_NUM 18271 -#define IMU_GYRO_Q_SENS_DEN 8383 -#define IMU_GYRO_R_SENS 2.17953 -#define IMU_GYRO_R_SENS_NUM 18271 -#define IMU_GYRO_R_SENS_DEN 8383 +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[DROTEK_2_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[DROTEK_2_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[DROTEK_2_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[DROTEK_2_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[DROTEK_2_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[DROTEK_2_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[DROTEK_2_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[DROTEK_2_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[DROTEK_2_GYRO_RANGE][1] #endif -/** default accel sensitivy from the datasheet - * MPU with 8g has 4096 LSB/g - * sens = 9.81 [m/s^2] / 4096 [LSB/g] * 2^INT32_ACCEL_FRAC = 2.4525 - */ +// Set default sensitivity based on range if needed #if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS -// FIXME -#define IMU_ACCEL_X_SENS 2.4525 -#define IMU_ACCEL_X_SENS_NUM 981 -#define IMU_ACCEL_X_SENS_DEN 400 -#define IMU_ACCEL_Y_SENS 2.4525 -#define IMU_ACCEL_Y_SENS_NUM 981 -#define IMU_ACCEL_Y_SENS_DEN 400 -#define IMU_ACCEL_Z_SENS 2.4525 -#define IMU_ACCEL_Z_SENS_NUM 981 -#define IMU_ACCEL_Z_SENS_DEN 400 +#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[DROTEK_2_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[DROTEK_2_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[DROTEK_2_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[DROTEK_2_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[DROTEK_2_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[DROTEK_2_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[DROTEK_2_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[DROTEK_2_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[DROTEK_2_ACCEL_RANGE][1] #endif + struct ImuDrotek2 { struct Mpu60x0_I2c mpu; struct Hmc58xx hmc; diff --git a/sw/airborne/subsystems/imu/imu_mpu6000.c b/sw/airborne/subsystems/imu/imu_mpu6000.c index 2457414d34..7cd3af302f 100644 --- a/sw/airborne/subsystems/imu/imu_mpu6000.c +++ b/sw/airborne/subsystems/imu/imu_mpu6000.c @@ -50,20 +50,13 @@ PRINT_CONFIG_MSG("Gyro/Accel output rate is 100Hz at 1kHz internal sampling") #define IMU_MPU_SMPLRT_DIV 3 PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling") #else -#error Non-default PERIODIC_FREQUENCY: please define MPU_HMC_LOWPASS_FILTER and MPU_HMC_SMPLRT_DIV. +#error Non-default PERIODIC_FREQUENCY: please define IMU_MPU_LOWPASS_FILTER and IMU_MPU_SMPLRT_DIV. #endif #endif PRINT_CONFIG_VAR(IMU_MPU_LOWPASS_FILTER) PRINT_CONFIG_VAR(IMU_MPU_SMPLRT_DIV) -#ifndef IMU_MPU_GYRO_RANGE -#define IMU_MPU_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 -#endif PRINT_CONFIG_VAR(IMU_MPU_GYRO_RANGE) - -#ifndef IMU_MPU_ACCEL_RANGE -#define IMU_MPU_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G -#endif PRINT_CONFIG_VAR(IMU_MPU_ACCEL_RANGE) diff --git a/sw/airborne/subsystems/imu/imu_mpu6000.h b/sw/airborne/subsystems/imu/imu_mpu6000.h index 369d77c439..07caacc935 100644 --- a/sw/airborne/subsystems/imu/imu_mpu6000.h +++ b/sw/airborne/subsystems/imu/imu_mpu6000.h @@ -31,9 +31,42 @@ #include "generated/airframe.h" #include "subsystems/imu.h" -#include "subsystems/imu/imu_mpu60x0_defaults.h" #include "peripherals/mpu60x0_spi.h" +#ifndef IMU_MPU_GYRO_RANGE +#define IMU_MPU_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 +#endif + +#ifndef IMU_MPU_ACCEL_RANGE +#define IMU_MPU_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[IMU_MPU_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[IMU_MPU_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[IMU_MPU_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][1] +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS +#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[IMU_MPU_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[IMU_MPU_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[IMU_MPU_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][1] +#endif + struct ImuMpu6000 { struct Mpu60x0_Spi mpu; diff --git a/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.c b/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.c index 8461fa76fd..36d9a4cb48 100644 --- a/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.c +++ b/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.c @@ -53,20 +53,13 @@ PRINT_CONFIG_MSG("Gyro/Accel output rate is 100Hz at 1kHz internal sampling") #define IMU_MPU_SMPLRT_DIV 3 PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling") #else -#error Non-default PERIODIC_FREQUENCY: please define MPU_HMC_LOWPASS_FILTER and MPU_HMC_SMPLRT_DIV. +#error Non-default PERIODIC_FREQUENCY: please define IMU_MPU_LOWPASS_FILTER and IMU_MPU_SMPLRT_DIV. #endif #endif PRINT_CONFIG_VAR(IMU_MPU_LOWPASS_FILTER) PRINT_CONFIG_VAR(IMU_MPU_SMPLRT_DIV) -#ifndef IMU_MPU_GYRO_RANGE -#define IMU_MPU_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 -#endif PRINT_CONFIG_VAR(IMU_MPU_GYRO_RANGE) - -#ifndef IMU_MPU_ACCEL_RANGE -#define IMU_MPU_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G -#endif PRINT_CONFIG_VAR(IMU_MPU_ACCEL_RANGE) // Default channels order diff --git a/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.h b/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.h index 04d34fc3e5..51e16e5d55 100644 --- a/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.h +++ b/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.h @@ -32,10 +32,43 @@ #include "generated/airframe.h" #include "subsystems/imu.h" -#include "subsystems/imu/imu_mpu60x0_defaults.h" #include "peripherals/mpu60x0_spi.h" #include "peripherals/hmc58xx.h" +#ifndef IMU_MPU_GYRO_RANGE +#define IMU_MPU_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 +#endif + +#ifndef IMU_MPU_ACCEL_RANGE +#define IMU_MPU_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[IMU_MPU_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[IMU_MPU_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[IMU_MPU_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[IMU_MPU_GYRO_RANGE][1] +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS +#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[IMU_MPU_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[IMU_MPU_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[IMU_MPU_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[IMU_MPU_ACCEL_RANGE][1] +#endif + struct ImuMpu6000Hmc5883 { struct Mpu60x0_Spi mpu; diff --git a/sw/airborne/subsystems/imu/imu_mpu60x0_defaults.h b/sw/airborne/subsystems/imu/imu_mpu60x0_defaults.h deleted file mode 100644 index 11b483624b..0000000000 --- a/sw/airborne/subsystems/imu/imu_mpu60x0_defaults.h +++ /dev/null @@ -1,66 +0,0 @@ -/* - * Copyright (C) 2013 Felix Ruess - * - * This file is part of paparazzi. - * - * paparazzi is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2, or (at your option) - * any later version. - * - * paparazzi is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with paparazzi; see the file COPYING. If not, write to - * the Free Software Foundation, 59 Temple Place - Suite 330, - * Boston, MA 02111-1307, USA. - */ - -/** - * @file subsystems/imu/imu_mpu60x0_defaults.h - * Default sensitivity definitions for an IMU using the MPU60x0. - */ - -#ifndef IMU_MPU60X0_DEFAULTS_H -#define IMU_MPU60X0_DEFAULTS_H - -#include "generated/airframe.h" - -/** default gyro sensitivy and neutral from the datasheet - * MPU60X0 has 16.4 LSB/(deg/s) at 2000deg/s range - * sens = 1/16.4 * pi/180 * 2^INT32_RATE_FRAC - * sens = 1/16.4 * pi/180 * 4096 = 4.359066229 - */ -#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS -#define IMU_GYRO_P_SENS 4.359 -#define IMU_GYRO_P_SENS_NUM 4359 -#define IMU_GYRO_P_SENS_DEN 1000 -#define IMU_GYRO_Q_SENS 4.359 -#define IMU_GYRO_Q_SENS_NUM 4359 -#define IMU_GYRO_Q_SENS_DEN 1000 -#define IMU_GYRO_R_SENS 4.359 -#define IMU_GYRO_R_SENS_NUM 4359 -#define IMU_GYRO_R_SENS_DEN 1000 -#endif - -/** default accel sensitivy from the datasheet - * MPU60X0 has 2048 LSB/g - * fixed point sens: 9.81 [m/s^2] / 2048 [LSB/g] * 2^INT32_ACCEL_FRAC - * sens = 9.81 / 2048 * 1024 = 4.905 - */ -#if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS -#define IMU_ACCEL_X_SENS 4.905 -#define IMU_ACCEL_X_SENS_NUM 4905 -#define IMU_ACCEL_X_SENS_DEN 1000 -#define IMU_ACCEL_Y_SENS 4.905 -#define IMU_ACCEL_Y_SENS_NUM 4905 -#define IMU_ACCEL_Y_SENS_DEN 1000 -#define IMU_ACCEL_Z_SENS 4.905 -#define IMU_ACCEL_Z_SENS_NUM 4905 -#define IMU_ACCEL_Z_SENS_DEN 1000 -#endif - -#endif /* IMU_MPU60X0_DEFAULTS_H */ diff --git a/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.c b/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.c index 0108ea3d69..2f19be084a 100644 --- a/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.c +++ b/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.c @@ -47,20 +47,13 @@ PRINT_CONFIG_MSG("Gyro/Accel output rate is 100Hz at 1kHz internal sampling") #define IMU_MPU60X0_SMPLRT_DIV 3 PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling") #else -#error Non-default PERIODIC_FREQUENCY: please define MPU60X0_HMC_LOWPASS_FILTER and MPU60X0_HMC_SMPLRT_DIV. +#error Non-default PERIODIC_FREQUENCY: please define IMU_MPU60X0_LOWPASS_FILTER and IMU_MPU60X0_SMPLRT_DIV. #endif #endif PRINT_CONFIG_VAR(IMU_MPU60X0_LOWPASS_FILTER) PRINT_CONFIG_VAR(IMU_MPU60X0_SMPLRT_DIV) -#ifndef IMU_MPU60X0_GYRO_RANGE -#define IMU_MPU60X0_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 -#endif PRINT_CONFIG_VAR(IMU_MPU60X0_GYRO_RANGE) - -#ifndef IMU_MPU60X0_ACCEL_RANGE -#define IMU_MPU60X0_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G -#endif PRINT_CONFIG_VAR(IMU_MPU60X0_ACCEL_RANGE) #ifndef IMU_MPU60X0_I2C_ADDR diff --git a/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.h b/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.h index 4ff1b4d233..2cfd311aef 100644 --- a/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.h +++ b/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.h @@ -31,9 +31,41 @@ #include "generated/airframe.h" #include "subsystems/imu.h" -#include "subsystems/imu/imu_mpu60x0_defaults.h" #include "peripherals/mpu60x0_i2c.h" +#ifndef IMU_MPU60X0_GYRO_RANGE +#define IMU_MPU60X0_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 +#endif + +#ifndef IMU_MPU60X0_ACCEL_RANGE +#define IMU_MPU60X0_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[IMU_MPU60X0_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[IMU_MPU60X0_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[IMU_MPU60X0_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[IMU_MPU60X0_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[IMU_MPU60X0_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[IMU_MPU60X0_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[IMU_MPU60X0_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[IMU_MPU60X0_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[IMU_MPU60X0_GYRO_RANGE][1] +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS +#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[IMU_MPU60X0_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[IMU_MPU60X0_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[IMU_MPU60X0_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[IMU_MPU60X0_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[IMU_MPU60X0_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[IMU_MPU60X0_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[IMU_MPU60X0_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[IMU_MPU60X0_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[IMU_MPU60X0_ACCEL_RANGE][1] +#endif struct ImuMpu60x0 { struct Mpu60x0_I2c mpu; diff --git a/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c b/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c index 9529035a0f..1fd4f52c21 100644 --- a/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c +++ b/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c @@ -61,14 +61,7 @@ PRINT_CONFIG_VAR(IMU_MPU9250_SMPLRT_DIV) PRINT_CONFIG_VAR(IMU_MPU9250_GYRO_LOWPASS_FILTER) PRINT_CONFIG_VAR(IMU_MPU9250_ACCEL_LOWPASS_FILTER) -#ifndef IMU_MPU9250_GYRO_RANGE -#define IMU_MPU9250_GYRO_RANGE MPU9250_GYRO_RANGE_1000 -#endif PRINT_CONFIG_VAR(IMU_MPU9250_GYRO_RANGE) - -#ifndef IMU_MPU9250_ACCEL_RANGE -#define IMU_MPU9250_ACCEL_RANGE MPU9250_ACCEL_RANGE_8G -#endif PRINT_CONFIG_VAR(IMU_MPU9250_ACCEL_RANGE) #ifndef IMU_MPU9250_I2C_ADDR diff --git a/sw/airborne/subsystems/imu/imu_mpu9250_i2c.h b/sw/airborne/subsystems/imu/imu_mpu9250_i2c.h index 4c7ab0567c..c5cb7940dd 100644 --- a/sw/airborne/subsystems/imu/imu_mpu9250_i2c.h +++ b/sw/airborne/subsystems/imu/imu_mpu9250_i2c.h @@ -35,39 +35,38 @@ #include "peripherals/mpu9250_i2c.h" -/** default gyro sensitivy and neutral from the datasheet - * MPU with 1000 deg/s has 32.8 LSB/(deg/s) - * sens = 1/32.8 * pi/180 * 2^INT32_RATE_FRAC - * sens = 1/32.8 * pi/180 * 4096 = 2.17953 - I*/ -#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS -// FIXME -#define IMU_GYRO_P_SENS 2.17953 -#define IMU_GYRO_P_SENS_NUM 18271 -#define IMU_GYRO_P_SENS_DEN 8383 -#define IMU_GYRO_Q_SENS 2.17953 -#define IMU_GYRO_Q_SENS_NUM 18271 -#define IMU_GYRO_Q_SENS_DEN 8383 -#define IMU_GYRO_R_SENS 2.17953 -#define IMU_GYRO_R_SENS_NUM 18271 -#define IMU_GYRO_R_SENS_DEN 8383 +#ifndef IMU_MPU9250_GYRO_RANGE +#define IMU_MPU9250_GYRO_RANGE MPU9250_GYRO_RANGE_1000 #endif -/** default accel sensitivy from the datasheet - * MPU with 8g has 4096 LSB/g - * sens = 9.81 [m/s^2] / 4096 [LSB/g] * 2^INT32_ACCEL_FRAC = 2.4525 - */ +#ifndef IMU_MPU9250_ACCEL_RANGE +#define IMU_MPU9250_ACCEL_RANGE MPU9250_ACCEL_RANGE_8G +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS MPU9250_GYRO_SENS[IMU_MPU9250_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU9250_GYRO_SENS[IMU_MPU9250_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU9250_GYRO_SENS[IMU_MPU9250_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][1] +#endif + +// Set default sensitivity based on range if needed #if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS -// FIXME -#define IMU_ACCEL_X_SENS 2.4525 -#define IMU_ACCEL_X_SENS_NUM 981 -#define IMU_ACCEL_X_SENS_DEN 400 -#define IMU_ACCEL_Y_SENS 2.4525 -#define IMU_ACCEL_Y_SENS_NUM 981 -#define IMU_ACCEL_Y_SENS_DEN 400 -#define IMU_ACCEL_Z_SENS 2.4525 -#define IMU_ACCEL_Z_SENS_NUM 981 -#define IMU_ACCEL_Z_SENS_DEN 400 +#define IMU_ACCEL_X_SENS MPU9250_ACCEL_SENS[IMU_MPU9250_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU9250_ACCEL_SENS[IMU_MPU9250_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU9250_ACCEL_SENS[IMU_MPU9250_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][1] #endif diff --git a/sw/airborne/subsystems/imu/imu_mpu9250_spi.c b/sw/airborne/subsystems/imu/imu_mpu9250_spi.c index 13cd64c5fe..746e530417 100644 --- a/sw/airborne/subsystems/imu/imu_mpu9250_spi.c +++ b/sw/airborne/subsystems/imu/imu_mpu9250_spi.c @@ -67,14 +67,7 @@ PRINT_CONFIG_VAR(IMU_MPU9250_SMPLRT_DIV) PRINT_CONFIG_VAR(IMU_MPU9250_GYRO_LOWPASS_FILTER) PRINT_CONFIG_VAR(IMU_MPU9250_ACCEL_LOWPASS_FILTER) -#ifndef IMU_MPU9250_GYRO_RANGE -#define IMU_MPU9250_GYRO_RANGE MPU9250_GYRO_RANGE_1000 -#endif PRINT_CONFIG_VAR(IMU_MPU9250_GYRO_RANGE) - -#ifndef IMU_MPU9250_ACCEL_RANGE -#define IMU_MPU9250_ACCEL_RANGE MPU9250_ACCEL_RANGE_8G -#endif PRINT_CONFIG_VAR(IMU_MPU9250_ACCEL_RANGE) // Default channels order diff --git a/sw/airborne/subsystems/imu/imu_mpu9250_spi.h b/sw/airborne/subsystems/imu/imu_mpu9250_spi.h index 3019a32b5c..22406bdca5 100644 --- a/sw/airborne/subsystems/imu/imu_mpu9250_spi.h +++ b/sw/airborne/subsystems/imu/imu_mpu9250_spi.h @@ -35,39 +35,38 @@ #include "peripherals/mpu9250_spi.h" -/** default gyro sensitivy and neutral from the datasheet - * MPU with 1000 deg/s has 32.8 LSB/(deg/s) - * sens = 1/32.8 * pi/180 * 2^INT32_RATE_FRAC - * sens = 1/32.8 * pi/180 * 4096 = 2.17953 - I*/ -#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS -// FIXME -#define IMU_GYRO_P_SENS 2.17953 -#define IMU_GYRO_P_SENS_NUM 18271 -#define IMU_GYRO_P_SENS_DEN 8383 -#define IMU_GYRO_Q_SENS 2.17953 -#define IMU_GYRO_Q_SENS_NUM 18271 -#define IMU_GYRO_Q_SENS_DEN 8383 -#define IMU_GYRO_R_SENS 2.17953 -#define IMU_GYRO_R_SENS_NUM 18271 -#define IMU_GYRO_R_SENS_DEN 8383 +#ifndef IMU_MPU9250_GYRO_RANGE +#define IMU_MPU9250_GYRO_RANGE MPU9250_GYRO_RANGE_1000 #endif -/** default accel sensitivy from the datasheet - * MPU with 8g has 4096 LSB/g - * sens = 9.81 [m/s^2] / 4096 [LSB/g] * 2^INT32_ACCEL_FRAC = 2.4525 - */ +#ifndef IMU_MPU9250_ACCEL_RANGE +#define IMU_MPU9250_ACCEL_RANGE MPU9250_ACCEL_RANGE_8G +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS MPU9250_GYRO_SENS[IMU_MPU9250_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU9250_GYRO_SENS[IMU_MPU9250_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU9250_GYRO_SENS[IMU_MPU9250_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU9250_GYRO_SENS_FRAC[IMU_MPU9250_GYRO_RANGE][1] +#endif + +// Set default sensitivity based on range if needed #if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS -// FIXME -#define IMU_ACCEL_X_SENS 2.4525 -#define IMU_ACCEL_X_SENS_NUM 981 -#define IMU_ACCEL_X_SENS_DEN 400 -#define IMU_ACCEL_Y_SENS 2.4525 -#define IMU_ACCEL_Y_SENS_NUM 981 -#define IMU_ACCEL_Y_SENS_DEN 400 -#define IMU_ACCEL_Z_SENS 2.4525 -#define IMU_ACCEL_Z_SENS_NUM 981 -#define IMU_ACCEL_Z_SENS_DEN 400 +#define IMU_ACCEL_X_SENS MPU9250_ACCEL_SENS[IMU_MPU9250_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU9250_ACCEL_SENS[IMU_MPU9250_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU9250_ACCEL_SENS[IMU_MPU9250_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU9250_ACCEL_SENS_FRAC[IMU_MPU9250_ACCEL_RANGE][1] #endif diff --git a/sw/airborne/subsystems/imu/imu_navstik.c b/sw/airborne/subsystems/imu/imu_navstik.c index 37db6e2686..10038e4e36 100644 --- a/sw/airborne/subsystems/imu/imu_navstik.c +++ b/sw/airborne/subsystems/imu/imu_navstik.c @@ -60,14 +60,7 @@ PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling") PRINT_CONFIG_VAR(NAVSTIK_SMPLRT_DIV) PRINT_CONFIG_VAR(NAVSTIK_LOWPASS_FILTER) -#ifndef NAVSTIK_GYRO_RANGE -#define NAVSTIK_GYRO_RANGE MPU60X0_GYRO_RANGE_1000 -#endif PRINT_CONFIG_VAR(NAVSTIK_GYRO_RANGE) - -#ifndef NAVSTIK_ACCEL_RANGE -#define NAVSTIK_ACCEL_RANGE MPU60X0_ACCEL_RANGE_8G -#endif PRINT_CONFIG_VAR(NAVSTIK_ACCEL_RANGE) /** Basic Navstik IMU data */ diff --git a/sw/airborne/subsystems/imu/imu_navstik.h b/sw/airborne/subsystems/imu/imu_navstik.h index 9abea9b558..7de296a281 100644 --- a/sw/airborne/subsystems/imu/imu_navstik.h +++ b/sw/airborne/subsystems/imu/imu_navstik.h @@ -34,39 +34,38 @@ #include "peripherals/hmc58xx.h" #include "peripherals/mpu60x0_i2c.h" -/** default gyro sensitivy and neutral from the datasheet - * MPU with 1000 deg/s has 32.8 LSB/(deg/s) - * sens = 1/32.8 * pi/180 * 2^INT32_RATE_FRAC - * sens = 1/32.8 * pi/180 * 4096 = 2.17953 - */ -#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS -// FIXME -#define IMU_GYRO_P_SENS 2.17953 -#define IMU_GYRO_P_SENS_NUM 18271 -#define IMU_GYRO_P_SENS_DEN 8383 -#define IMU_GYRO_Q_SENS 2.17953 -#define IMU_GYRO_Q_SENS_NUM 18271 -#define IMU_GYRO_Q_SENS_DEN 8383 -#define IMU_GYRO_R_SENS 2.17953 -#define IMU_GYRO_R_SENS_NUM 18271 -#define IMU_GYRO_R_SENS_DEN 8383 +#ifndef NAVSTIK_GYRO_RANGE +#define NAVSTIK_GYRO_RANGE MPU60X0_GYRO_RANGE_1000 #endif -/** default accel sensitivy from the datasheet - * MPU with 8g has 4096 LSB/g - * sens = 9.81 [m/s^2] / 4096 [LSB/g] * 2^INT32_ACCEL_FRAC = 2.4525 - */ +#ifndef NAVSTIK_ACCEL_RANGE +#define NAVSTIK_ACCEL_RANGE MPU60X0_ACCEL_RANGE_8G +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[NAVSTIK_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[NAVSTIK_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[NAVSTIK_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[NAVSTIK_GYRO_RANGE][1] +#endif + +// Set default sensitivity based on range if needed #if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS -// FIXME -#define IMU_ACCEL_X_SENS 2.4525 -#define IMU_ACCEL_X_SENS_NUM 981 -#define IMU_ACCEL_X_SENS_DEN 400 -#define IMU_ACCEL_Y_SENS 2.4525 -#define IMU_ACCEL_Y_SENS_NUM 981 -#define IMU_ACCEL_Y_SENS_DEN 400 -#define IMU_ACCEL_Z_SENS 2.4525 -#define IMU_ACCEL_Z_SENS_NUM 981 -#define IMU_ACCEL_Z_SENS_DEN 400 +#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[NAVSTIK_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[NAVSTIK_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[NAVSTIK_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[NAVSTIK_ACCEL_RANGE][1] #endif diff --git a/sw/airborne/subsystems/imu/imu_px4fmu.c b/sw/airborne/subsystems/imu/imu_px4fmu.c index a14c68a11b..2fd2e303dd 100644 --- a/sw/airborne/subsystems/imu/imu_px4fmu.c +++ b/sw/airborne/subsystems/imu/imu_px4fmu.c @@ -53,14 +53,7 @@ PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling") PRINT_CONFIG_VAR(PX4FMU_LOWPASS_FILTER) PRINT_CONFIG_VAR(PX4FMU_SMPLRT_DIV) -#ifndef PX4FMU_GYRO_RANGE -#define PX4FMU_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 -#endif PRINT_CONFIG_VAR(PX4FMU_GYRO_RANGE) - -#ifndef PX4FMU_ACCEL_RANGE -#define PX4FMU_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G -#endif PRINT_CONFIG_VAR(PX4FMU_ACCEL_RANGE) struct ImuPx4fmu imu_px4fmu; diff --git a/sw/airborne/subsystems/imu/imu_px4fmu.h b/sw/airborne/subsystems/imu/imu_px4fmu.h index d6584c21e6..dc4a736001 100644 --- a/sw/airborne/subsystems/imu/imu_px4fmu.h +++ b/sw/airborne/subsystems/imu/imu_px4fmu.h @@ -31,10 +31,44 @@ #include "generated/airframe.h" #include "subsystems/imu.h" -#include "subsystems/imu/imu_mpu60x0_defaults.h" #include "peripherals/mpu60x0_spi.h" #include "peripherals/hmc58xx.h" +#ifndef PX4FMU_GYRO_RANGE +#define PX4FMU_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 +#endif +PRINT_CONFIG_VAR(PX4FMU_GYRO_RANGE) + +#ifndef PX4FMU_ACCEL_RANGE +#define PX4FMU_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_GYRO_P_SENS & !defined IMU_GYRO_Q_SENS & !defined IMU_GYRO_R_SENS +#define IMU_GYRO_P_SENS MPU60X0_GYRO_SENS[PX4FMU_GYRO_RANGE] +#define IMU_GYRO_P_SENS_NUM MPU60X0_GYRO_SENS_FRAC[PX4FMU_GYRO_RANGE][0] +#define IMU_GYRO_P_SENS_DEN MPU60X0_GYRO_SENS_FRAC[PX4FMU_GYRO_RANGE][1] +#define IMU_GYRO_Q_SENS MPU60X0_GYRO_SENS[PX4FMU_GYRO_RANGE] +#define IMU_GYRO_Q_SENS_NUM MPU60X0_GYRO_SENS_FRAC[PX4FMU_GYRO_RANGE][0] +#define IMU_GYRO_Q_SENS_DEN MPU60X0_GYRO_SENS_FRAC[PX4FMU_GYRO_RANGE][1] +#define IMU_GYRO_R_SENS MPU60X0_GYRO_SENS[PX4FMU_GYRO_RANGE] +#define IMU_GYRO_R_SENS_NUM MPU60X0_GYRO_SENS_FRAC[PX4FMU_GYRO_RANGE][0] +#define IMU_GYRO_R_SENS_DEN MPU60X0_GYRO_SENS_FRAC[PX4FMU_GYRO_RANGE][1] +#endif + +// Set default sensitivity based on range if needed +#if !defined IMU_ACCEL_X_SENS & !defined IMU_ACCEL_Y_SENS & !defined IMU_ACCEL_Z_SENS +#define IMU_ACCEL_X_SENS MPU60X0_ACCEL_SENS[PX4FMU_ACCEL_RANGE] +#define IMU_ACCEL_X_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[PX4FMU_ACCEL_RANGE][0] +#define IMU_ACCEL_X_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[PX4FMU_ACCEL_RANGE][1] +#define IMU_ACCEL_Y_SENS MPU60X0_ACCEL_SENS[PX4FMU_ACCEL_RANGE] +#define IMU_ACCEL_Y_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[PX4FMU_ACCEL_RANGE][0] +#define IMU_ACCEL_Y_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[PX4FMU_ACCEL_RANGE][1] +#define IMU_ACCEL_Z_SENS MPU60X0_ACCEL_SENS[PX4FMU_ACCEL_RANGE] +#define IMU_ACCEL_Z_SENS_NUM MPU60X0_ACCEL_SENS_FRAC[PX4FMU_ACCEL_RANGE][0] +#define IMU_ACCEL_Z_SENS_DEN MPU60X0_ACCEL_SENS_FRAC[PX4FMU_ACCEL_RANGE][1] +#endif + struct ImuPx4fmu { struct Mpu60x0_Spi mpu; struct Hmc58xx hmc;