mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 14:55:21 +03:00
althold constants updated
baro velocity now limited to 15m/s d-term is now smaller Conflicts: src/imu.c
This commit is contained in:
parent
1bf806f54c
commit
75f94aa11b
1 changed files with 7 additions and 7 deletions
|
@ -405,12 +405,12 @@ int32_t calculateBaroPid(int32_t vel_tmp, float accZ_tmp, float accZ_old)
|
||||||
newBaroPID = constrain((pidProfile->P8[PIDVEL] * error / 32), -300, +300);
|
newBaroPID = constrain((pidProfile->P8[PIDVEL] * error / 32), -300, +300);
|
||||||
|
|
||||||
// I
|
// I
|
||||||
errorAltitudeI += (pidProfile->I8[PIDVEL] * error) / 8;
|
errorAltitudeI += (pidProfile->I8[PIDVEL] * error);
|
||||||
errorAltitudeI = constrain(errorAltitudeI, -(1024 * 200), (1024 * 200));
|
errorAltitudeI = constrain(errorAltitudeI, -(8196 * 200), (8196 * 200));
|
||||||
newBaroPID += errorAltitudeI / 1024; // I in range +/-200
|
newBaroPID += errorAltitudeI / 8196; // I in range +/-200
|
||||||
|
|
||||||
// D
|
// D
|
||||||
newBaroPID -= constrain(pidProfile->D8[PIDVEL] * (accZ_tmp + accZ_old) / 64, -150, 150);
|
newBaroPID -= constrain(pidProfile->D8[PIDVEL] * (accZ_tmp + accZ_old) / 512, -150, 150);
|
||||||
|
|
||||||
return newBaroPID;
|
return newBaroPID;
|
||||||
}
|
}
|
||||||
|
@ -476,7 +476,7 @@ void calculateEstimatedAltitude(uint32_t currentTime)
|
||||||
|
|
||||||
// Integrator - Altitude in cm
|
// Integrator - Altitude in cm
|
||||||
accAlt += (vel_acc * 0.5f) * dt + vel * dt; // integrate velocity to get distance (x= a/2 * t^2)
|
accAlt += (vel_acc * 0.5f) * dt + vel * dt; // integrate velocity to get distance (x= a/2 * t^2)
|
||||||
accAlt = accAlt * barometerConfig->baro_cf_alt + (float)BaroAlt * (1.0f - 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)
|
||||||
vel += vel_acc;
|
vel += vel_acc;
|
||||||
|
|
||||||
#if 1
|
#if 1
|
||||||
|
@ -501,7 +501,7 @@ void calculateEstimatedAltitude(uint32_t currentTime)
|
||||||
baroVel = (BaroAlt - lastBaroAlt) * 1000000.0f / dTime;
|
baroVel = (BaroAlt - lastBaroAlt) * 1000000.0f / dTime;
|
||||||
lastBaroAlt = BaroAlt;
|
lastBaroAlt = BaroAlt;
|
||||||
|
|
||||||
baroVel = constrain(baroVel, -300, 300); // constrain baro velocity +/- 300cm/s
|
baroVel = constrain(baroVel, -1500, 1500); // constrain baro velocity +/- 1500cm/s
|
||||||
baroVel = applyDeadband(baroVel, 10); // to reduce noise near zero
|
baroVel = applyDeadband(baroVel, 10); // to reduce noise near zero
|
||||||
|
|
||||||
// apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity).
|
// apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity).
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue