From 51eee3d62c9adbff0a469e2731b32f7340b60d09 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Fri, 6 Jun 2014 20:59:59 +0100 Subject: [PATCH] Decoupling imu from config - barometer config. --- src/main/config/config.c | 2 +- src/main/flight/imu.c | 8 +++++--- src/main/flight/imu.h | 2 +- src/main/mw.c | 14 +++++++------- 4 files changed, 14 insertions(+), 12 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index e840aa6fdb..b0b6aa89a6 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -389,7 +389,7 @@ void activateConfig(void) imuRuntimeConfig.gyro_cmpfm_factor = masterConfig.gyro_cmpfm_factor; imuRuntimeConfig.acc_lpf_factor = currentProfile.acc_lpf_factor; - configureImu(&imuRuntimeConfig, ¤tProfile.pidProfile); + configureImu(&imuRuntimeConfig, ¤tProfile.pidProfile, ¤tProfile.barometerConfig); calculateThrottleAngleScale(currentProfile.throttle_correction_angle); diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index 703d6016bb..13592d9005 100755 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -106,11 +106,13 @@ void calculateThrottleAngleScale(uint16_t throttle_correction_angle) imuRuntimeConfig_t *imuRuntimeConfig; pidProfile_t *pidProfile; +barometerConfig_t *barometerConfig; -void configureImu(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile) +void configureImu(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile, barometerConfig_t *intialBarometerConfig) { imuRuntimeConfig = initialImuRuntimeConfig; pidProfile = initialPidProfile; + barometerConfig = intialBarometerConfig; } void computeIMU(rollAndPitchTrims_t *accelerometerTrims) @@ -455,7 +457,7 @@ int getEstimatedAltitude(void) // Integrator - Altitude in cm accAlt += (vel_acc * 0.5f) * dt + vel * dt; // integrate velocity to get distance (x= a/2 * t^2) - accAlt = accAlt * currentProfile.barometerConfig.baro_cf_alt + (float)BaroAlt * (1.0f - currentProfile.barometerConfig.baro_cf_alt); // complementary filter for Altitude estimation (baro & acc) + accAlt = accAlt * barometerConfig->baro_cf_alt + (float)BaroAlt * (1.0f - barometerConfig->baro_cf_alt); // complementary filter for Altitude estimation (baro & acc) EstAlt = accAlt; vel += vel_acc; @@ -475,7 +477,7 @@ int getEstimatedAltitude(void) // apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity). // By using CF it's possible to correct the drift of integrated accZ (velocity) without loosing the phase, i.e without delay - vel = vel * currentProfile.barometerConfig.baro_cf_vel + baroVel * (1 - currentProfile.barometerConfig.baro_cf_vel); + vel = vel * barometerConfig->baro_cf_vel + baroVel * (1 - barometerConfig->baro_cf_vel); vel_tmp = lrintf(vel); // set vario diff --git a/src/main/flight/imu.h b/src/main/flight/imu.h index 4222a322d4..c52dd48400 100644 --- a/src/main/flight/imu.h +++ b/src/main/flight/imu.h @@ -27,7 +27,7 @@ typedef struct imuRuntimeConfig_s { float gyro_cmpfm_factor; } imuRuntimeConfig_t; -void configureImu(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile); +void configureImu(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile, barometerConfig_t *intialBarometerConfig); int getEstimatedAltitude(void); void computeIMU(rollAndPitchTrims_t *accelerometerTrims); diff --git a/src/main/mw.c b/src/main/mw.c index b2473e892d..40da1277d5 100755 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -32,23 +32,23 @@ #include "drivers/system.h" #include "drivers/serial.h" +#include "flight/flight.h" +#include "sensors/sensors.h" #include "sensors/boardalignment.h" +#include "sensors/sonar.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/gyro.h" #include "sensors/battery.h" #include "io/buzzer.h" #include "io/escservo.h" -#include "flight/flight.h" #include "flight/failsafe.h" #include "flight/imu.h" #include "flight/autotune.h" #include "flight/mixer.h" #include "io/gimbal.h" #include "io/gps.h" -#include "sensors/sensors.h" -#include "sensors/sonar.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/gyro.h" #include "io/serial_cli.h" #include "io/serial.h" #include "io/statusindicator.h"