mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 14:25:20 +03:00
AltHold cleanup.
* Renamed several methods and variables so they make more sense. * Move more altitude hold related code out of imu.c/h into altitudehold.c/h. * Fixed a unsigned integer being using instead of an signed integer in the throttle calculation code.
This commit is contained in:
parent
7d4abb8a4a
commit
daa823ddba
8 changed files with 222 additions and 199 deletions
|
@ -20,8 +20,11 @@
|
|||
extern int32_t errorVelocityI;
|
||||
extern uint8_t velocityControl;
|
||||
extern int32_t setVelocity;
|
||||
extern int32_t BaroPID;
|
||||
extern int32_t altHoldThrottleAdjustment;
|
||||
extern int16_t throttleAngleCorrection;
|
||||
extern uint32_t accTimeSum;
|
||||
extern int accSumCount;
|
||||
extern float accVelScale;
|
||||
|
||||
typedef struct imuRuntimeConfig_s {
|
||||
uint8_t acc_lpf_factor;
|
||||
|
@ -31,10 +34,12 @@ typedef struct imuRuntimeConfig_s {
|
|||
int8_t small_angle;
|
||||
} imuRuntimeConfig_t;
|
||||
|
||||
void configureImu(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile, barometerConfig_t *intialBarometerConfig, accDeadband_t *initialAccDeadband);
|
||||
void configureImu(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile, accDeadband_t *initialAccDeadband);
|
||||
|
||||
void calculateEstimatedAltitude(uint32_t currentTime);
|
||||
void computeIMU(rollAndPitchTrims_t *accelerometerTrims, uint8_t mixerConfiguration);
|
||||
void calculateThrottleAngleScale(uint16_t throttle_correction_angle);
|
||||
int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value);
|
||||
void calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_cutoff);
|
||||
|
||||
void accSum_reset(void);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue