mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-19 14:25:16 +03:00
Fix bugs in gain scaling; Allow gain scaling for NAV PID
This commit is contained in:
parent
89e86bbc8b
commit
8666edc80e
3 changed files with 24 additions and 15 deletions
|
@ -1330,13 +1330,13 @@ static void navProcessFSMEvents(navigationFSMEvent_t injectedEvent)
|
||||||
// Implementation of PID with back-calculation I-term anti-windup
|
// Implementation of PID with back-calculation I-term anti-windup
|
||||||
// Control System Design, Lecture Notes for ME 155A by Karl Johan Åström (p.228)
|
// Control System Design, Lecture Notes for ME 155A by Karl Johan Åström (p.228)
|
||||||
// http://www.cds.caltech.edu/~murray/courses/cds101/fa02/caltech/astrom-ch6.pdf
|
// http://www.cds.caltech.edu/~murray/courses/cds101/fa02/caltech/astrom-ch6.pdf
|
||||||
float navPidApply2(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags)
|
float navPidApply3(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags, const float gainScaler)
|
||||||
{
|
{
|
||||||
float newProportional, newDerivative;
|
float newProportional, newDerivative;
|
||||||
float error = setpoint - measurement;
|
float error = setpoint - measurement;
|
||||||
|
|
||||||
/* P-term */
|
/* P-term */
|
||||||
newProportional = error * pid->param.kP;
|
newProportional = error * pid->param.kP * gainScaler;
|
||||||
|
|
||||||
/* D-term */
|
/* D-term */
|
||||||
if (pidFlags & PID_DTERM_FROM_ERROR) {
|
if (pidFlags & PID_DTERM_FROM_ERROR) {
|
||||||
|
@ -1350,19 +1350,19 @@ float navPidApply2(pidController_t *pid, const float setpoint, const float measu
|
||||||
pid->last_input = measurement;
|
pid->last_input = measurement;
|
||||||
}
|
}
|
||||||
|
|
||||||
newDerivative = pid->param.kD * pt1FilterApply4(&pid->dterm_filter_state, newDerivative, NAV_DTERM_CUT_HZ, dt);
|
newDerivative = pid->param.kD * pt1FilterApply4(&pid->dterm_filter_state, newDerivative, NAV_DTERM_CUT_HZ, dt) * gainScaler;
|
||||||
|
|
||||||
if (pidFlags & PID_ZERO_INTEGRATOR) {
|
if (pidFlags & PID_ZERO_INTEGRATOR) {
|
||||||
pid->integrator = 0.0f;
|
pid->integrator = 0.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Pre-calculate output and limit it if actuator is saturating */
|
/* Pre-calculate output and limit it if actuator is saturating */
|
||||||
const float outVal = newProportional + pid->integrator + newDerivative;
|
const float outVal = newProportional + (pid->integrator * gainScaler) + newDerivative;
|
||||||
const float outValConstrained = constrainf(outVal, outMin, outMax);
|
const float outValConstrained = constrainf(outVal, outMin, outMax);
|
||||||
|
|
||||||
/* Update I-term */
|
/* Update I-term */
|
||||||
if (!(pidFlags & PID_ZERO_INTEGRATOR)) {
|
if (!(pidFlags & PID_ZERO_INTEGRATOR)) {
|
||||||
const float newIntegrator = pid->integrator + (error * pid->param.kI * dt) + ((outValConstrained - outVal) * pid->param.kT * dt);
|
const float newIntegrator = pid->integrator + (error * pid->param.kI * gainScaler * dt) + ((outValConstrained - outVal) * pid->param.kT * dt);
|
||||||
|
|
||||||
if (pidFlags & PID_SHRINK_INTEGRATOR) {
|
if (pidFlags & PID_SHRINK_INTEGRATOR) {
|
||||||
// Only allow integrator to shrink
|
// Only allow integrator to shrink
|
||||||
|
@ -1378,6 +1378,12 @@ float navPidApply2(pidController_t *pid, const float setpoint, const float measu
|
||||||
return outValConstrained;
|
return outValConstrained;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
float navPidApply2(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags)
|
||||||
|
{
|
||||||
|
return navPidApply3(pid, setpoint, measurement, dt, outMin, outMax, pidFlags, 1.0f);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
void navPidReset(pidController_t *pid)
|
void navPidReset(pidController_t *pid)
|
||||||
{
|
{
|
||||||
pid->integrator = 0.0f;
|
pid->integrator = 0.0f;
|
||||||
|
@ -2605,9 +2611,9 @@ void navigationUsePIDs(void)
|
||||||
(float)pidProfile()->bank_fw.pid[PID_POS_XY].I / 100.0f,
|
(float)pidProfile()->bank_fw.pid[PID_POS_XY].I / 100.0f,
|
||||||
(float)pidProfile()->bank_fw.pid[PID_POS_XY].D / 100.0f);
|
(float)pidProfile()->bank_fw.pid[PID_POS_XY].D / 100.0f);
|
||||||
|
|
||||||
navPidInit(&posControl.pids.fw_alt, (float)pidProfile()->bank_fw.pid[PID_POS_Z].P,
|
navPidInit(&posControl.pids.fw_alt, (float)pidProfile()->bank_fw.pid[PID_POS_Z].P / 9.80665f,
|
||||||
(float)pidProfile()->bank_fw.pid[PID_POS_Z].I,
|
(float)pidProfile()->bank_fw.pid[PID_POS_Z].I / 9.80665f,
|
||||||
(float)pidProfile()->bank_fw.pid[PID_POS_Z].D);
|
(float)pidProfile()->bank_fw.pid[PID_POS_Z].D / 9.80665f);
|
||||||
}
|
}
|
||||||
|
|
||||||
void navigationInit(void)
|
void navigationInit(void)
|
||||||
|
|
|
@ -110,22 +110,24 @@ static void updateAltitudeVelocityAndPitchController_FW(timeDelta_t deltaMicros)
|
||||||
const float estSPE = (posControl.actualState.pos.V.Z / 100.0f) * GRAVITY_MSS;
|
const float estSPE = (posControl.actualState.pos.V.Z / 100.0f) * GRAVITY_MSS;
|
||||||
const float estSKE = 0.0f;
|
const float estSKE = 0.0f;
|
||||||
|
|
||||||
|
// speedWeight controls balance between potential and kinetic energy used for pitch controller
|
||||||
|
// speedWeight = 1.0 : pitch will only control airspeed and won't control altitude
|
||||||
|
// speedWeight = 0.5 : pitch will be used to control both airspeed and altitude
|
||||||
|
// speedWeight = 0.0 : pitch will only control altitude
|
||||||
const float speedWeight = 0.0f; // no speed sensing for now
|
const float speedWeight = 0.0f; // no speed sensing for now
|
||||||
|
|
||||||
const float wSKE = speedWeight;
|
const float demSEB = demSPE * (1.0f - speedWeight) - demSKE * speedWeight;
|
||||||
const float wSPE = 1.0f - speedWeight;
|
const float estSEB = estSPE * (1.0f - speedWeight) - estSKE * speedWeight;
|
||||||
const float demSEB = demSPE * wSPE - demSKE * wSKE;
|
|
||||||
const float estSEB = estSPE * wSPE - estSKE * wSKE;
|
|
||||||
|
|
||||||
// SEB to pitch angle gain to account for airspeed
|
// SEB to pitch angle gain to account for airspeed (with respect to specified reference (tuning) speed
|
||||||
const float pitchGainInv = GRAVITY_MSS; // GRAVITY_MSS * airspeed;
|
const float pitchGainInv = 1.0f / 1.0f;
|
||||||
|
|
||||||
// Here we use negative values for dive for better clarity
|
// Here we use negative values for dive for better clarity
|
||||||
const float maxClimbDeciDeg = DEGREES_TO_DECIDEGREES(navConfig()->fw.max_climb_angle);
|
const float maxClimbDeciDeg = DEGREES_TO_DECIDEGREES(navConfig()->fw.max_climb_angle);
|
||||||
const float minDiveDeciDeg = -DEGREES_TO_DECIDEGREES(navConfig()->fw.max_dive_angle);
|
const float minDiveDeciDeg = -DEGREES_TO_DECIDEGREES(navConfig()->fw.max_dive_angle);
|
||||||
|
|
||||||
// PID controller to translate energy balance error [J] into pitch angle [decideg]
|
// PID controller to translate energy balance error [J] into pitch angle [decideg]
|
||||||
float targetPitchAngle = navPidApply2(&posControl.pids.fw_alt, demSEB, estSEB, US2S(deltaMicros), minDiveDeciDeg, maxClimbDeciDeg, 0) / pitchGainInv;
|
float targetPitchAngle = navPidApply3(&posControl.pids.fw_alt, demSEB, estSEB, US2S(deltaMicros), minDiveDeciDeg, maxClimbDeciDeg, 0, pitchGainInv);
|
||||||
targetPitchAngle = pt1FilterApply4(&velzFilterState, targetPitchAngle, NAV_FW_PITCH_CUTOFF_FREQENCY_HZ, US2S(deltaMicros));
|
targetPitchAngle = pt1FilterApply4(&velzFilterState, targetPitchAngle, NAV_FW_PITCH_CUTOFF_FREQENCY_HZ, US2S(deltaMicros));
|
||||||
|
|
||||||
// Reconstrain pitch angle ( >0 - climb, <0 - dive)
|
// Reconstrain pitch angle ( >0 - climb, <0 - dive)
|
||||||
|
|
|
@ -296,6 +296,7 @@ extern navigationPosControl_t posControl;
|
||||||
|
|
||||||
/* Internally used functions */
|
/* Internally used functions */
|
||||||
float navPidApply2(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags);
|
float navPidApply2(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags);
|
||||||
|
float navPidApply3(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags, const float gainScaler);
|
||||||
void navPidReset(pidController_t *pid);
|
void navPidReset(pidController_t *pid);
|
||||||
void navPidInit(pidController_t *pid, float _kP, float _kI, float _kD);
|
void navPidInit(pidController_t *pid, float _kP, float _kI, float _kD);
|
||||||
void navPInit(pController_t *p, float _kP);
|
void navPInit(pController_t *p, float _kP);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue