1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 21:35:44 +03:00

Merge pull request #4616 from martinbudden/bfa_pid_deltat_us

Scaled PID deltaT calculations from us to seconds
This commit is contained in:
Martin Budden 2017-11-19 04:58:59 +00:00 committed by GitHub
commit e7d2e84348
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23

View file

@ -411,11 +411,11 @@ void pidController(const pidProfile_t *pidProfile, const rollAndPitchTrims_t *an
const float tpaFactor = getThrottlePIDAttenuation();
const float motorMixRange = getMotorMixRange();
static timeUs_t crashDetectedAtUs;
static timeUs_t previousTime;
static timeUs_t previousTimeUs;
// calculate actual deltaT
const float deltaT = currentTimeUs - previousTime;
previousTime = currentTimeUs;
// calculate actual deltaT in seconds
const float deltaT = (currentTimeUs - previousTimeUs) * 0.000001f;
previousTimeUs = currentTimeUs;
// Dynamic ki component to gradually scale back integration when above windup point
const float dynKi = MIN((1.0f - motorMixRange) * ITermWindupPointInv, 1.0f);