1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 14:25:20 +03:00

Moved configuring of IMU all into one function call.

This commit is contained in:
Pierre Hugo 2015-01-23 23:03:22 -08:00
parent be03ed95fa
commit d691f72849
3 changed files with 28 additions and 12 deletions

View file

@ -30,12 +30,18 @@ typedef struct imuRuntimeConfig_s {
int8_t small_angle;
} imuRuntimeConfig_t;
void configureIMU(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile, accDeadband_t *initialAccDeadband);
void configureIMU(
imuRuntimeConfig_t *initialImuRuntimeConfig,
pidProfile_t *initialPidProfile,
accDeadband_t *initialAccDeadband,
float accz_lpf_cutoff,
uint16_t throttle_correction_angle
);
void calculateEstimatedAltitude(uint32_t currentTime);
void computeIMU(rollAndPitchTrims_t *accelerometerTrims, uint8_t mixerMode);
void calculateThrottleAngleScale(uint16_t throttle_correction_angle);
float calculateThrottleAngleScale(uint16_t throttle_correction_angle);
int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value);
void calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_cutoff);
float calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_cutoff);
void accSum_reset(void);