PID code cleanup // refactoring
This commit is contained in:
parent
4e3704374a
commit
1030df294d
|
@ -1261,8 +1261,8 @@ static bool blackboxWriteSysinfo()
|
||||||
BLACKBOX_PRINT_HEADER_LINE("itermThrottleThreshold:%d", currentProfile->pidProfile.itermThrottleThreshold);
|
BLACKBOX_PRINT_HEADER_LINE("itermThrottleThreshold:%d", currentProfile->pidProfile.itermThrottleThreshold);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("setpointRelaxRatio:%d", currentProfile->pidProfile.setpointRelaxRatio);
|
BLACKBOX_PRINT_HEADER_LINE("setpointRelaxRatio:%d", currentProfile->pidProfile.setpointRelaxRatio);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("dtermSetpointWeight:%d", currentProfile->pidProfile.dtermSetpointWeight);
|
BLACKBOX_PRINT_HEADER_LINE("dtermSetpointWeight:%d", currentProfile->pidProfile.dtermSetpointWeight);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit:%d", currentProfile->pidProfile.yawRateAccelLimit);
|
BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit:%d", castFloatBytesToInt(currentProfile->pidProfile.yawRateAccelLimit));
|
||||||
BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", currentProfile->pidProfile.rateAccelLimit);
|
BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", castFloatBytesToInt(currentProfile->pidProfile.rateAccelLimit));
|
||||||
// End of Betaflight controller parameters
|
// End of Betaflight controller parameters
|
||||||
|
|
||||||
BLACKBOX_PRINT_HEADER_LINE("deadband:%d", rcControlsConfig()->deadband);
|
BLACKBOX_PRINT_HEADER_LINE("deadband:%d", rcControlsConfig()->deadband);
|
||||||
|
|
|
@ -176,12 +176,13 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
||||||
pidProfile->dterm_notch_cutoff = 160;
|
pidProfile->dterm_notch_cutoff = 160;
|
||||||
pidProfile->vbatPidCompensation = 0;
|
pidProfile->vbatPidCompensation = 0;
|
||||||
pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
|
pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
|
||||||
|
pidProfile->max_angle_inclination = 70.0f; // 70 degrees
|
||||||
|
|
||||||
// Betaflight PID controller parameters
|
// Betaflight PID controller parameters
|
||||||
pidProfile->setpointRelaxRatio = 30;
|
pidProfile->setpointRelaxRatio = 30;
|
||||||
pidProfile->dtermSetpointWeight = 200;
|
pidProfile->dtermSetpointWeight = 200;
|
||||||
pidProfile->yawRateAccelLimit = 220;
|
pidProfile->yawRateAccelLimit = 20.0f;
|
||||||
pidProfile->rateAccelLimit = 0;
|
pidProfile->rateAccelLimit = 0.0f;
|
||||||
pidProfile->itermThrottleThreshold = 350;
|
pidProfile->itermThrottleThreshold = 350;
|
||||||
pidProfile->levelSensitivity = 2.0f;
|
pidProfile->levelSensitivity = 2.0f;
|
||||||
}
|
}
|
||||||
|
@ -612,7 +613,6 @@ void createDefaultConfig(master_t *config)
|
||||||
config->gyroConfig.gyro_sync_denom = 4;
|
config->gyroConfig.gyro_sync_denom = 4;
|
||||||
config->pidConfig.pid_process_denom = 2;
|
config->pidConfig.pid_process_denom = 2;
|
||||||
#endif
|
#endif
|
||||||
config->pidConfig.max_angle_inclination = 700; // 70 degrees
|
|
||||||
config->gyroConfig.gyro_soft_lpf_type = FILTER_PT1;
|
config->gyroConfig.gyro_soft_lpf_type = FILTER_PT1;
|
||||||
config->gyroConfig.gyro_soft_lpf_hz = 90;
|
config->gyroConfig.gyro_soft_lpf_hz = 90;
|
||||||
config->gyroConfig.gyro_soft_notch_hz_1 = 400;
|
config->gyroConfig.gyro_soft_notch_hz_1 = 400;
|
||||||
|
|
|
@ -92,13 +92,25 @@ uint8_t motorControlEnable = false;
|
||||||
int16_t telemTemperature1; // gyro sensor temperature
|
int16_t telemTemperature1; // gyro sensor temperature
|
||||||
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
||||||
|
|
||||||
extern uint8_t PIDweight[3];
|
static float throttlePIDAttenuation;
|
||||||
|
|
||||||
uint16_t filteredCycleTime;
|
uint16_t filteredCycleTime;
|
||||||
bool isRXDataNew;
|
bool isRXDataNew;
|
||||||
static bool armingCalibrationWasInitialised;
|
static bool armingCalibrationWasInitialised;
|
||||||
float setpointRate[3];
|
static float setpointRate[3];
|
||||||
float rcInput[3];
|
static float rcDeflection[3];
|
||||||
|
|
||||||
|
float getThrottlePIDAttenuation(void) {
|
||||||
|
return throttlePIDAttenuation;
|
||||||
|
}
|
||||||
|
|
||||||
|
float getSetpointRate(int axis) {
|
||||||
|
return setpointRate[axis];
|
||||||
|
}
|
||||||
|
|
||||||
|
float getRcDeflection(int axis) {
|
||||||
|
return rcDeflection[axis];
|
||||||
|
}
|
||||||
|
|
||||||
void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta)
|
void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta)
|
||||||
{
|
{
|
||||||
|
@ -137,11 +149,11 @@ void calculateSetpointRate(int axis, int16_t rc) {
|
||||||
|
|
||||||
if (rcRate > 2.0f) rcRate = rcRate + (RC_RATE_INCREMENTAL * (rcRate - 2.0f));
|
if (rcRate > 2.0f) rcRate = rcRate + (RC_RATE_INCREMENTAL * (rcRate - 2.0f));
|
||||||
rcCommandf = rc / 500.0f;
|
rcCommandf = rc / 500.0f;
|
||||||
rcInput[axis] = ABS(rcCommandf);
|
rcDeflection[axis] = ABS(rcCommandf);
|
||||||
|
|
||||||
if (rcExpo) {
|
if (rcExpo) {
|
||||||
float expof = rcExpo / 100.0f;
|
float expof = rcExpo / 100.0f;
|
||||||
rcCommandf = rcCommandf * power3(rcInput[axis]) * expof + rcCommandf * (1-expof);
|
rcCommandf = rcCommandf * power3(rcDeflection[axis]) * expof + rcCommandf * (1-expof);
|
||||||
}
|
}
|
||||||
|
|
||||||
angleRate = 200.0f * rcRate * rcCommandf;
|
angleRate = 200.0f * rcRate * rcCommandf;
|
||||||
|
@ -270,17 +282,18 @@ void updateRcCommands(void)
|
||||||
int32_t prop;
|
int32_t prop;
|
||||||
if (rcData[THROTTLE] < currentControlRateProfile->tpa_breakpoint) {
|
if (rcData[THROTTLE] < currentControlRateProfile->tpa_breakpoint) {
|
||||||
prop = 100;
|
prop = 100;
|
||||||
|
throttlePIDAttenuation = 1.0f;
|
||||||
} else {
|
} else {
|
||||||
if (rcData[THROTTLE] < 2000) {
|
if (rcData[THROTTLE] < 2000) {
|
||||||
prop = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint);
|
prop = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint);
|
||||||
} else {
|
} else {
|
||||||
prop = 100 - currentControlRateProfile->dynThrPID;
|
prop = 100 - currentControlRateProfile->dynThrPID;
|
||||||
}
|
}
|
||||||
|
throttlePIDAttenuation = prop / 100.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int axis = 0; axis < 3; axis++) {
|
for (int axis = 0; axis < 3; axis++) {
|
||||||
// non coupled PID reduction scaler used in PID controller 1 and PID controller 2.
|
// non coupled PID reduction scaler used in PID controller 1 and PID controller 2.
|
||||||
PIDweight[axis] = prop;
|
|
||||||
|
|
||||||
int32_t tmp = MIN(ABS(rcData[axis] - rxConfig()->midrc), 500);
|
int32_t tmp = MIN(ABS(rcData[axis] - rxConfig()->midrc), 500);
|
||||||
if (axis == ROLL || axis == PITCH) {
|
if (axis == ROLL || axis == PITCH) {
|
||||||
|
@ -679,9 +692,7 @@ void subTaskPidController(void)
|
||||||
// PID - note this is function pointer set by setPIDController()
|
// PID - note this is function pointer set by setPIDController()
|
||||||
pidController(
|
pidController(
|
||||||
¤tProfile->pidProfile,
|
¤tProfile->pidProfile,
|
||||||
pidConfig()->max_angle_inclination,
|
&accelerometerConfig()->accelerometerTrims
|
||||||
&accelerometerConfig()->accelerometerTrims,
|
|
||||||
rxConfig()->midrc
|
|
||||||
);
|
);
|
||||||
if (debugMode == DEBUG_PIDLOOP || debugMode == DEBUG_SCHEDULER) {debug[1] = micros() - startTime;}
|
if (debugMode == DEBUG_PIDLOOP || debugMode == DEBUG_SCHEDULER) {debug[1] = micros() - startTime;}
|
||||||
}
|
}
|
||||||
|
|
|
@ -34,3 +34,6 @@ void updateLEDs(void);
|
||||||
void updateRcCommands(void);
|
void updateRcCommands(void);
|
||||||
|
|
||||||
void taskMainPidLoop(timeUs_t currentTimeUs);
|
void taskMainPidLoop(timeUs_t currentTimeUs);
|
||||||
|
float getThrottlePIDAttenuation(void);
|
||||||
|
float getSetpointRate(int axis);
|
||||||
|
float getRcDeflection(int axis);
|
||||||
|
|
|
@ -1164,8 +1164,8 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
||||||
sbufWriteU8(dst, 0); // reserved
|
sbufWriteU8(dst, 0); // reserved
|
||||||
sbufWriteU8(dst, 0); // reserved
|
sbufWriteU8(dst, 0); // reserved
|
||||||
sbufWriteU8(dst, 0); // reserved
|
sbufWriteU8(dst, 0); // reserved
|
||||||
sbufWriteU16(dst, currentProfile->pidProfile.rateAccelLimit);
|
sbufWriteU16(dst, currentProfile->pidProfile.rateAccelLimit * 10);
|
||||||
sbufWriteU16(dst, currentProfile->pidProfile.yawRateAccelLimit);
|
sbufWriteU16(dst, currentProfile->pidProfile.yawRateAccelLimit * 10);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_SENSOR_CONFIG:
|
case MSP_SENSOR_CONFIG:
|
||||||
|
@ -1512,8 +1512,8 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
sbufReadU8(src); // reserved
|
sbufReadU8(src); // reserved
|
||||||
sbufReadU8(src); // reserved
|
sbufReadU8(src); // reserved
|
||||||
sbufReadU8(src); // reserved
|
sbufReadU8(src); // reserved
|
||||||
currentProfile->pidProfile.rateAccelLimit = sbufReadU16(src);
|
currentProfile->pidProfile.rateAccelLimit = sbufReadU16(src) / 10.0f;
|
||||||
currentProfile->pidProfile.yawRateAccelLimit = sbufReadU16(src);
|
currentProfile->pidProfile.yawRateAccelLimit = sbufReadU16(src) / 10.0f;
|
||||||
pidInitConfig(¤tProfile->pidProfile);
|
pidInitConfig(¤tProfile->pidProfile);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
|
|
@ -28,6 +28,7 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/filter.h"
|
#include "common/filter.h"
|
||||||
|
|
||||||
|
#include "fc/fc_main.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
@ -38,17 +39,11 @@
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
|
|
||||||
extern float rcInput[3];
|
|
||||||
extern float setpointRate[3];
|
|
||||||
|
|
||||||
uint32_t targetPidLooptime;
|
uint32_t targetPidLooptime;
|
||||||
static bool pidStabilisationEnabled;
|
static bool pidStabilisationEnabled;
|
||||||
|
|
||||||
float axisPIDf[3];
|
float axisPIDf[3];
|
||||||
|
|
||||||
// PIDweight is a scale factor for PIDs which is derived from the throttle and TPA setting, and 100 = 100% scale means no PID reduction
|
|
||||||
uint8_t PIDweight[3];
|
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef BLACKBOX
|
||||||
int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
||||||
#endif
|
#endif
|
||||||
|
@ -145,8 +140,7 @@ void pidInitFilters(const pidProfile_t *pidProfile)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static float Kp[3], Ki[3], Kd[3], c[3];
|
static float Kp[3], Ki[3], Kd[3], c[3], levelGain, horizonGain, horizonTransition, maxVelocity[3], relaxFactor[3];
|
||||||
static float rollPitchMaxVelocity, yawMaxVelocity, relaxFactor[3];
|
|
||||||
|
|
||||||
void pidInitConfig(const pidProfile_t *pidProfile) {
|
void pidInitConfig(const pidProfile_t *pidProfile) {
|
||||||
for(int axis = FD_ROLL; axis <= FD_YAW; axis++) {
|
for(int axis = FD_ROLL; axis <= FD_YAW; axis++) {
|
||||||
|
@ -156,70 +150,85 @@ void pidInitConfig(const pidProfile_t *pidProfile) {
|
||||||
c[axis] = pidProfile->dtermSetpointWeight / 100.0f;
|
c[axis] = pidProfile->dtermSetpointWeight / 100.0f;
|
||||||
relaxFactor[axis] = 1.0f - (pidProfile->setpointRelaxRatio / 100.0f);
|
relaxFactor[axis] = 1.0f - (pidProfile->setpointRelaxRatio / 100.0f);
|
||||||
}
|
}
|
||||||
yawMaxVelocity = pidProfile->yawRateAccelLimit * 1000 * dT;
|
levelGain = pidProfile->P8[PIDLEVEL] / 10.0f;
|
||||||
rollPitchMaxVelocity = pidProfile->rateAccelLimit * 1000 * dT;
|
horizonGain = pidProfile->I8[PIDLEVEL] / 10.0f;
|
||||||
|
horizonTransition = 100.0f / pidProfile->D8[PIDLEVEL];
|
||||||
|
maxVelocity[FD_ROLL] = maxVelocity[FD_PITCH] = pidProfile->rateAccelLimit * 1000 * dT;
|
||||||
|
maxVelocity[FD_YAW] = pidProfile->yawRateAccelLimit * 1000 * dT;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage.
|
float currentPidSetpoint = 0, horizonLevelStrength = 1.0f;
|
||||||
// Based on 2DOF reference design (matlab)
|
|
||||||
void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, uint16_t midrc)
|
|
||||||
{
|
|
||||||
static float previousRateError[2];
|
|
||||||
static float previousSetpoint[3];
|
|
||||||
|
|
||||||
float horizonLevelStrength = 1;
|
void calcHorizonLevelStrength(const pidProfile_t *pidProfile) {
|
||||||
if (FLIGHT_MODE(HORIZON_MODE)) {
|
const float mostDeflectedPos = MAX(getRcDeflection(FD_ROLL), getRcDeflection(FD_PITCH));
|
||||||
// Figure out the raw stick positions
|
|
||||||
const int32_t stickPosAil = ABS(getRcStickDeflection(FD_ROLL, midrc));
|
|
||||||
const int32_t stickPosEle = ABS(getRcStickDeflection(FD_PITCH, midrc));
|
|
||||||
const int32_t mostDeflectedPos = MAX(stickPosAil, stickPosEle);
|
|
||||||
// Progressively turn off the horizon self level strength as the stick is banged over
|
// Progressively turn off the horizon self level strength as the stick is banged over
|
||||||
horizonLevelStrength = (float)(500 - mostDeflectedPos) / 500; // 1 at centre stick, 0 = max stick deflection
|
horizonLevelStrength = (1.0f - mostDeflectedPos); // 1 at centre stick, 0 = max stick deflection
|
||||||
if(pidProfile->D8[PIDLEVEL] == 0){
|
if(pidProfile->D8[PIDLEVEL] == 0){
|
||||||
horizonLevelStrength = 0;
|
horizonLevelStrength = 0;
|
||||||
} else {
|
} else {
|
||||||
horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * (100 / pidProfile->D8[PIDLEVEL])) + 1, 0, 1);
|
horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * horizonTransition) + 1, 0, 1);
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// ----------PID controller----------
|
void pidLevel(int axis, const pidProfile_t *pidProfile, const rollAndPitchTrims_t *angleTrim) {
|
||||||
const float tpaFactor = PIDweight[0] / 100.0f; // tpa is now float
|
|
||||||
for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {
|
|
||||||
// Limit abrupt yaw inputs / stops
|
|
||||||
const float maxVelocity = (axis == FD_YAW) ? yawMaxVelocity : rollPitchMaxVelocity;
|
|
||||||
if (maxVelocity) {
|
|
||||||
const float currentVelocity = setpointRate[axis] - previousSetpoint[axis];
|
|
||||||
if (ABS(currentVelocity) > maxVelocity) {
|
|
||||||
setpointRate[axis] = (currentVelocity > 0) ? previousSetpoint[axis] + maxVelocity : previousSetpoint[axis] - maxVelocity;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Yaw control is GYRO based, direct sticks control is applied to rate PID
|
|
||||||
if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && axis != YAW) {
|
|
||||||
// calculate error angle and limit the angle to the max inclination
|
// calculate error angle and limit the angle to the max inclination
|
||||||
float errorAngle = pidProfile->levelSensitivity * rcCommand[axis];
|
float errorAngle = pidProfile->levelSensitivity * rcCommand[axis];
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
errorAngle += GPS_angle[axis];
|
errorAngle += GPS_angle[axis];
|
||||||
#endif
|
#endif
|
||||||
errorAngle = constrainf(errorAngle, -max_angle_inclination, max_angle_inclination);
|
errorAngle = constrainf(errorAngle, -pidProfile->max_angle_inclination, pidProfile->max_angle_inclination);
|
||||||
errorAngle = (errorAngle - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f;
|
errorAngle = (errorAngle - ((attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f));
|
||||||
if (FLIGHT_MODE(ANGLE_MODE)) {
|
if(FLIGHT_MODE(ANGLE_MODE)) {
|
||||||
// ANGLE mode - control is angle based, so control loop is needed
|
// ANGLE mode - control is angle based, so control loop is needed
|
||||||
setpointRate[axis] = errorAngle * pidProfile->P8[PIDLEVEL] / 10.0f;
|
currentPidSetpoint = errorAngle * levelGain;
|
||||||
} else {
|
} else {
|
||||||
// HORIZON mode - direct sticks control is applied to rate PID
|
// HORIZON mode - direct sticks control is applied to rate PID
|
||||||
// mix up angle error to desired AngleRate to add a little auto-level feel
|
// mix up angle error to desired AngleRate to add a little auto-level feel
|
||||||
setpointRate[axis] = setpointRate[axis] + (errorAngle * pidProfile->I8[PIDLEVEL] * horizonLevelStrength / 10.0f);
|
currentPidSetpoint = currentPidSetpoint + (errorAngle * horizonGain * horizonLevelStrength);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void accelerationLimit(int axis) {
|
||||||
|
static float previousSetpoint[3];
|
||||||
|
const float currentVelocity = currentPidSetpoint- previousSetpoint[axis];
|
||||||
|
|
||||||
|
if(ABS(currentVelocity) > maxVelocity[axis])
|
||||||
|
currentPidSetpoint = (currentVelocity > 0) ? previousSetpoint[axis] + maxVelocity[axis] : previousSetpoint[axis] - maxVelocity[axis];
|
||||||
|
|
||||||
|
previousSetpoint[axis] = currentPidSetpoint;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage.
|
||||||
|
// Based on 2DOF reference design (matlab)
|
||||||
|
void pidController(const pidProfile_t *pidProfile, const rollAndPitchTrims_t *angleTrim)
|
||||||
|
{
|
||||||
|
static float previousRateError[2];
|
||||||
|
static float previousSetpoint[3];
|
||||||
|
|
||||||
|
if(FLIGHT_MODE(HORIZON_MODE))
|
||||||
|
calcHorizonLevelStrength(pidProfile);
|
||||||
|
|
||||||
|
// ----------PID controller----------
|
||||||
|
const float tpaFactor = getThrottlePIDAttenuation();
|
||||||
|
|
||||||
|
for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {
|
||||||
|
currentPidSetpoint = getSetpointRate(axis);
|
||||||
|
|
||||||
|
if(maxVelocity[axis])
|
||||||
|
accelerationLimit(axis);
|
||||||
|
|
||||||
|
// Yaw control is GYRO based, direct sticks control is applied to rate PID
|
||||||
|
if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && axis != YAW) {
|
||||||
|
pidLevel(axis, pidProfile, angleTrim);
|
||||||
}
|
}
|
||||||
|
|
||||||
const float PVRate = gyro.gyroADCf[axis]; // Process variable from gyro output in deg/sec
|
const float gyroRate = gyro.gyroADCf[axis]; // Process variable from gyro output in deg/sec
|
||||||
|
|
||||||
// --------low-level gyro-based PID based on 2DOF PID controller. ----------
|
// --------low-level gyro-based PID based on 2DOF PID controller. ----------
|
||||||
// ---------- 2-DOF PID controller with optional filter on derivative term. b = 1 and only c can be tuned (amount derivative on measurement or error). ----------
|
// ---------- 2-DOF PID controller with optional filter on derivative term. b = 1 and only c can be tuned (amount derivative on measurement or error). ----------
|
||||||
|
|
||||||
// -----calculate error rate
|
// -----calculate error rate
|
||||||
const float errorRate = setpointRate[axis] - PVRate; // r - y
|
const float errorRate = currentPidSetpoint - gyroRate; // r - y
|
||||||
|
|
||||||
// -----calculate P component and add Dynamic Part based on stick input
|
// -----calculate P component and add Dynamic Part based on stick input
|
||||||
float PTerm = Kp[axis] * errorRate * tpaFactor;
|
float PTerm = Kp[axis] * errorRate * tpaFactor;
|
||||||
|
@ -227,7 +236,7 @@ void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
|
||||||
// -----calculate I component
|
// -----calculate I component
|
||||||
// Reduce strong Iterm accumulation during higher stick inputs
|
// Reduce strong Iterm accumulation during higher stick inputs
|
||||||
const float accumulationThreshold = (axis == FD_YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate;
|
const float accumulationThreshold = (axis == FD_YAW) ? pidProfile->yawItermIgnoreRate : pidProfile->rollPitchItermIgnoreRate;
|
||||||
const float setpointRateScaler = constrainf(1.0f - (ABS(setpointRate[axis]) / accumulationThreshold), 0.0f, 1.0f);
|
const float setpointRateScaler = constrainf(1.0f - (ABS(currentPidSetpoint) / accumulationThreshold), 0.0f, 1.0f);
|
||||||
|
|
||||||
float ITerm = previousGyroIf[axis];
|
float ITerm = previousGyroIf[axis];
|
||||||
ITerm += Ki[axis] * errorRate * dT * setpointRateScaler;
|
ITerm += Ki[axis] * errorRate * dT * setpointRateScaler;
|
||||||
|
@ -240,16 +249,17 @@ void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
|
||||||
if (axis != FD_YAW) {
|
if (axis != FD_YAW) {
|
||||||
float dynC = c[axis];
|
float dynC = c[axis];
|
||||||
if (pidProfile->setpointRelaxRatio < 100) {
|
if (pidProfile->setpointRelaxRatio < 100) {
|
||||||
|
const float rcDeflection = getRcDeflection(axis);
|
||||||
dynC = c[axis];
|
dynC = c[axis];
|
||||||
if (setpointRate[axis] > 0) {
|
if (currentPidSetpoint > 0) {
|
||||||
if ((setpointRate[axis] - previousSetpoint[axis]) < previousSetpoint[axis])
|
if ((currentPidSetpoint - previousSetpoint[axis]) < previousSetpoint[axis])
|
||||||
dynC = dynC * sq(rcInput[axis]) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]);
|
dynC = dynC * sq(rcDeflection) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]);
|
||||||
} else if (setpointRate[axis] < 0) {
|
} else if (currentPidSetpoint < 0) {
|
||||||
if ((setpointRate[axis] - previousSetpoint[axis]) > previousSetpoint[axis])
|
if ((currentPidSetpoint - previousSetpoint[axis]) > previousSetpoint[axis])
|
||||||
dynC = dynC * sq(rcInput[axis]) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]);
|
dynC = dynC * sq(rcDeflection) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
const float rD = dynC * setpointRate[axis] - PVRate; // cr - y
|
const float rD = dynC * currentPidSetpoint - gyroRate; // cr - y
|
||||||
// Divide rate change by dT to get differential (ie dr/dt)
|
// Divide rate change by dT to get differential (ie dr/dt)
|
||||||
const float delta = (rD - previousRateError[axis]) / dT;
|
const float delta = (rD - previousRateError[axis]) / dT;
|
||||||
previousRateError[axis] = rD;
|
previousRateError[axis] = rD;
|
||||||
|
@ -264,7 +274,7 @@ void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio
|
||||||
} else {
|
} else {
|
||||||
PTerm = ptermYawFilterApplyFn(ptermYawFilter, PTerm);
|
PTerm = ptermYawFilterApplyFn(ptermYawFilter, PTerm);
|
||||||
}
|
}
|
||||||
previousSetpoint[axis] = setpointRate[axis];
|
previousSetpoint[axis] = currentPidSetpoint;
|
||||||
|
|
||||||
// -----calculate total PID output
|
// -----calculate total PID output
|
||||||
axisPIDf[axis] = PTerm + ITerm + DTerm;
|
axisPIDf[axis] = PTerm + ITerm + DTerm;
|
||||||
|
|
|
@ -72,23 +72,23 @@ typedef struct pidProfile_s {
|
||||||
uint8_t dterm_average_count; // Configurable delta count for dterm
|
uint8_t dterm_average_count; // Configurable delta count for dterm
|
||||||
uint8_t vbatPidCompensation; // Scale PIDsum to battery voltage
|
uint8_t vbatPidCompensation; // Scale PIDsum to battery voltage
|
||||||
uint8_t pidAtMinThrottle; // Disable/Enable pids on zero throttle. Normally even without airmode P and D would be active.
|
uint8_t pidAtMinThrottle; // Disable/Enable pids on zero throttle. Normally even without airmode P and D would be active.
|
||||||
|
float max_angle_inclination;
|
||||||
|
|
||||||
// Betaflight PID controller parameters
|
// Betaflight PID controller parameters
|
||||||
uint16_t itermThrottleThreshold; // max allowed throttle delta before errorGyroReset in ms
|
uint16_t itermThrottleThreshold; // max allowed throttle delta before errorGyroReset in ms
|
||||||
uint8_t setpointRelaxRatio; // Setpoint weight relaxation effect
|
uint8_t setpointRelaxRatio; // Setpoint weight relaxation effect
|
||||||
uint8_t dtermSetpointWeight; // Setpoint weight for Dterm (0= measurement, 1= full error, 1 > agressive derivative)
|
uint8_t dtermSetpointWeight; // Setpoint weight for Dterm (0= measurement, 1= full error, 1 > agressive derivative)
|
||||||
uint16_t yawRateAccelLimit; // yaw accel limiter for deg/sec/ms
|
float yawRateAccelLimit; // yaw accel limiter for deg/sec/ms
|
||||||
uint16_t rateAccelLimit; // accel limiter roll/pitch deg/sec/ms
|
float rateAccelLimit; // accel limiter roll/pitch deg/sec/ms
|
||||||
float levelSensitivity;
|
float levelSensitivity;
|
||||||
} pidProfile_t;
|
} pidProfile_t;
|
||||||
|
|
||||||
typedef struct pidConfig_s {
|
typedef struct pidConfig_s {
|
||||||
uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
|
uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
|
||||||
uint16_t max_angle_inclination;
|
|
||||||
} pidConfig_t;
|
} pidConfig_t;
|
||||||
|
|
||||||
union rollAndPitchTrims_u;
|
union rollAndPitchTrims_u;
|
||||||
void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, const union rollAndPitchTrims_u *angleTrim, uint16_t midrc);
|
void pidController(const pidProfile_t *pidProfile, const union rollAndPitchTrims_u *angleTrim);
|
||||||
|
|
||||||
extern float axisPIDf[3];
|
extern float axisPIDf[3];
|
||||||
extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
||||||
|
|
|
@ -835,7 +835,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &mixerConfig()->yaw_motor_direction, .config.minmax = { -1, 1 } },
|
{ "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &mixerConfig()->yaw_motor_direction, .config.minmax = { -1, 1 } },
|
||||||
{ "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
|
{ "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
|
||||||
{ "pidsum_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pidSumLimit, .config.minmax = { 0.1, 1.0 } },
|
{ "pidsum_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pidSumLimit, .config.minmax = { 0.1, 1.0 } },
|
||||||
{ "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &pidConfig()->max_angle_inclination, .config.minmax = { 100, 900 } },
|
{ "max_angle_inclination", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.max_angle_inclination, .config.minmax = { 10.0f, 120.0f } },
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
||||||
{ "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoMixerConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
|
{ "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoMixerConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
|
||||||
|
@ -894,11 +894,11 @@ const clivalue_t valueTable[] = {
|
||||||
{ "dterm_notch_cutoff", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_notch_cutoff, .config.minmax = { 1, 500 } },
|
{ "dterm_notch_cutoff", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_notch_cutoff, .config.minmax = { 1, 500 } },
|
||||||
{ "vbat_pid_compensation", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
|
{ "vbat_pid_compensation", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
|
||||||
{ "pid_at_min_throttle", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidAtMinThrottle, .config.lookup = { TABLE_OFF_ON } },
|
{ "pid_at_min_throttle", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidAtMinThrottle, .config.lookup = { TABLE_OFF_ON } },
|
||||||
{ "iterm_throttle_reset", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleThreshold, .config.minmax = {20, 1000 } },
|
{ "anti_gravity_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleThreshold, .config.minmax = {20, 1000 } },
|
||||||
{ "setpoint_relax_ratio", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.setpointRelaxRatio, .config.minmax = {0, 100 } },
|
{ "setpoint_relax_ratio", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.setpointRelaxRatio, .config.minmax = {0, 100 } },
|
||||||
{ "dterm_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dtermSetpointWeight, .config.minmax = {0, 255 } },
|
{ "dterm_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dtermSetpointWeight, .config.minmax = {0, 255 } },
|
||||||
{ "yaw_rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawRateAccelLimit, .config.minmax = {0, 1000 } },
|
{ "yaw_accel_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawRateAccelLimit, .config.minmax = {0.1f, 50.0f } },
|
||||||
{ "rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rateAccelLimit, .config.minmax = {0, 1000 } },
|
{ "accel_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rateAccelLimit, .config.minmax = {0.1f, 50.0f } },
|
||||||
|
|
||||||
{ "accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
|
{ "accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||||
{ "yaw_accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
|
{ "yaw_accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||||
|
|
Loading…
Reference in New Issue