1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

Angle and Horizon Mode improvements (#12231)

* Angle and Horizon Update for 4.5

* BugFix FF noise Angle Mode on yaw and in level _race mode

* use time constant in ms for angle feedforward smoothing

* refactor to remove unnecessary definition

---------

Co-authored-by: ChrisRosser <chrisrosser91@gmail.com>
This commit is contained in:
ctzsnooze 2023-03-15 09:46:24 +11:00 committed by GitHub
parent d6ed53ecdf
commit 241e9a9b94
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
16 changed files with 482 additions and 271 deletions

View file

@ -128,7 +128,7 @@ void resetPidProfile(pidProfile_t *pidProfile)
[PID_ROLL] = PID_ROLL_DEFAULT,
[PID_PITCH] = PID_PITCH_DEFAULT,
[PID_YAW] = PID_YAW_DEFAULT,
[PID_LEVEL] = { 50, 50, 75, 0 },
[PID_LEVEL] = { 50, 50, 75, 50 },
[PID_MAG] = { 40, 0, 0, 0 },
},
.pidSumLimit = PIDSUM_LIMIT,
@ -138,7 +138,7 @@ void resetPidProfile(pidProfile_t *pidProfile)
.dterm_notch_cutoff = 0,
.itermWindupPointPercent = 85,
.pidAtMinThrottle = PID_STABILISATION_ON,
.levelAngleLimit = 55,
.angle_limit = 60,
.feedforward_transition = 0,
.yawRateAccelLimit = 0,
.rateAccelLimit = 0,
@ -151,8 +151,8 @@ void resetPidProfile(pidProfile_t *pidProfile)
.crash_gthreshold = 400, // degrees/second
.crash_setpoint_threshold = 350, // degrees/second
.crash_recovery = PID_CRASH_RECOVERY_OFF, // off by default
.horizon_tilt_effect = 75,
.horizon_tilt_expert_mode = false,
.horizon_limit_degrees = 135,
.horizon_ignore_sticks = false,
.crash_limit_yaw = 200,
.itermLimit = 400,
.throttle_boost = 5,
@ -224,6 +224,8 @@ void resetPidProfile(pidProfile_t *pidProfile)
.tpa_mode = TPA_MODE_D,
.tpa_rate = 65,
.tpa_breakpoint = 1350,
.angle_feedforward_smoothing_ms = 80,
.angle_earth_ref = 100,
);
#ifndef USE_D_MIN
@ -365,9 +367,9 @@ float pidApplyThrustLinearization(float motorOutput)
#if defined(USE_ACC)
// calculate the stick deflection while applying level mode expo
static float getLevelModeRcDeflection(uint8_t axis)
static float getAngleModeStickInputRaw(uint8_t axis)
{
const float stickDeflection = getRcDeflection(axis);
const float stickDeflection = getRcDeflectionRaw(axis);
if (axis < FD_YAW) {
const float expof = currentControlRateProfile->levelExpo[axis] / 100.0f;
return power3(stickDeflection) * expof + stickDeflection * (1 - expof);
@ -379,86 +381,127 @@ static float getLevelModeRcDeflection(uint8_t axis)
// calculates strength of horizon leveling; 0 = none, 1.0 = most leveling
STATIC_UNIT_TESTED FAST_CODE_NOINLINE float calcHorizonLevelStrength(void)
{
// start with 1.0 at center stick, 0.0 at max stick deflection:
float horizonLevelStrength = 1.0f - MAX(fabsf(getLevelModeRcDeflection(FD_ROLL)), fabsf(getLevelModeRcDeflection(FD_PITCH)));
// 0 at level, 90 at vertical, 180 at inverted (degrees):
const float currentInclination = MAX(abs(attitude.values.roll), abs(attitude.values.pitch)) / 10.0f;
// 0 when level, 90 when vertical, 180 when inverted (degrees):
float horizonLevelStrength = MAX((pidRuntime.horizonLimitDegrees - currentInclination) / pidRuntime.horizonLimitDegrees, 0.0f);
// 1.0 when attitude is 'flat', 0 when angle is equal to, or greater than, horizonLimitDegrees
// horizonTiltExpertMode: 0 = leveling always active when sticks centered,
// 1 = leveling can be totally off when inverted
if (pidRuntime.horizonTiltExpertMode) {
if (pidRuntime.horizonTransition > 0 && pidRuntime.horizonCutoffDegrees > 0) {
// if d_level > 0 and horizonTiltEffect < 175
// horizonCutoffDegrees: 0 to 125 => 270 to 90 (represents where leveling goes to zero)
// inclinationLevelRatio (0.0 to 1.0) is smaller (less leveling)
// for larger inclinations; 0.0 at horizonCutoffDegrees value:
const float inclinationLevelRatio = constrainf((pidRuntime.horizonCutoffDegrees-currentInclination) / pidRuntime.horizonCutoffDegrees, 0, 1);
// apply configured horizon sensitivity:
// when stick is near center (horizonLevelStrength ~= 1.0)
// H_sensitivity value has little effect,
// when stick is deflected (horizonLevelStrength near 0.0)
// H_sensitivity value has more effect:
horizonLevelStrength = (horizonLevelStrength - 1) * 100 / pidRuntime.horizonTransition + 1;
// apply inclination ratio, which may lower leveling
// to zero regardless of stick position:
horizonLevelStrength *= inclinationLevelRatio;
} else { // d_level=0 or horizon_tilt_effect>=175 means no leveling
horizonLevelStrength = 0;
}
} else { // horizon_tilt_expert_mode = 0 (leveling always active when sticks centered)
float sensitFact;
if (pidRuntime.horizonFactorRatio < 1.0f) { // if horizonTiltEffect > 0
// horizonFactorRatio: 1.0 to 0.0 (larger means more leveling)
// inclinationLevelRatio (0.0 to 1.0) is smaller (less leveling)
// for larger inclinations, goes to 1.0 at inclination==level:
const float inclinationLevelRatio = (180 - currentInclination) / 180 * (1.0f - pidRuntime.horizonFactorRatio) + pidRuntime.horizonFactorRatio;
// apply ratio to configured horizon sensitivity:
sensitFact = pidRuntime.horizonTransition * inclinationLevelRatio;
} else { // horizonTiltEffect=0 for "old" functionality
sensitFact = pidRuntime.horizonTransition;
}
if (sensitFact <= 0) { // zero means no leveling
horizonLevelStrength = 0;
} else {
// when stick is near center (horizonLevelStrength ~= 1.0)
// sensitFact value has little effect,
// when stick is deflected (horizonLevelStrength near 0.0)
// sensitFact value has more effect:
horizonLevelStrength = ((horizonLevelStrength - 1) * (100 / sensitFact)) + 1;
}
if (!pidRuntime.horizonIgnoreSticks) {
// horizonIgnoreSticks: 0 = default; levelling attenuated by both attitude and sticks;
// 1 = level attenuation only by attitude
const float absMaxStickDeflection = MAX(fabsf(getRcDeflection(FD_ROLL)), fabsf(getRcDeflection(FD_PITCH))); // 0-1, smoothed if RC smoothing is enabled
const float horizonStickAttenuation = MAX((pidRuntime.horizonLimitSticks - absMaxStickDeflection) / pidRuntime.horizonLimitSticks, 0.0f);
// 1.0 at center stick, 0.0 at max stick deflection:
horizonLevelStrength *= horizonStickAttenuation * pidRuntime.horizonGain;
}
return constrainf(horizonLevelStrength, 0, 1);
return horizonLevelStrength;
}
// Use the FAST_CODE_NOINLINE directive to avoid this code from being inlined into ITCM RAM to avoid overflow.
// The impact is possibly slightly slower performance on F7/H7 but they have more than enough
// processing power that it should be a non-issue.
STATIC_UNIT_TESTED FAST_CODE_NOINLINE float pidLevel(int axis, const pidProfile_t *pidProfile, const rollAndPitchTrims_t *angleTrim,
float currentPidSetpoint, float horizonLevelStrength)
float rawSetpoint, float horizonLevelStrength, bool newRcFrame)
{
const float levelAngleLimit = pidProfile->levelAngleLimit;
// calculate error angle and limit the angle to the max inclination
// rcDeflection is in range [-1.0, 1.0]
float angle = levelAngleLimit * getLevelModeRcDeflection(axis);
#ifdef USE_GPS_RESCUE
angle += gpsRescueAngle[axis] / 100; // ANGLE IS IN CENTIDEGREES
#endif
angle = constrainf(angle, -levelAngleLimit, levelAngleLimit);
const float errorAngle = angle - ((attitude.raw[axis] - angleTrim->raw[axis]) / 10.0f);
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(GPS_RESCUE_MODE)) {
// ANGLE mode - control is angle based
const float setpointCorrection = errorAngle * pidRuntime.levelGain;
currentPidSetpoint = pt3FilterApply(&pidRuntime.attitudeFilter[axis], setpointCorrection);
} else {
// HORIZON mode - mix of ANGLE and ACRO modes
// mix in errorAngle to currentPidSetpoint to add a little auto-level feel
const float setpointCorrection = errorAngle * pidRuntime.horizonGain * horizonLevelStrength;
currentPidSetpoint += pt3FilterApply(&pidRuntime.attitudeFilter[axis], setpointCorrection);
const float angleLimit = pidProfile->angle_limit;
// ** angle loop feedforward
float angleFeedforward = 0.0f;
#ifdef USE_FEEDFORWARD
const float rxRateHz = 1e6f / getCurrentRxRefreshRate();
const float rcCommandDeltaAbs = fabsf(getRcCommandDelta(axis));
if (newRcFrame){
// this runs at Rx link rate
const float angleTargetRaw = angleLimit * getAngleModeStickInputRaw(axis);
float angleFeedforwardInput = 0.0f;
if (rcCommandDeltaAbs) {
// there is movement, so calculate a Delta value to get feedforward
pidRuntime.angleTargetDelta[axis] = (angleTargetRaw - pidRuntime.angleTargetPrevious[axis]);
angleFeedforwardInput = pidRuntime.angleTargetDelta[axis];
pidRuntime.angleDuplicateCount[axis] = 0;
pidRuntime.angleTargetPrevious[axis] = angleTargetRaw;
// no need for averaging or PT1 smoothing because of the strong PT3 smoothing of the final value
} else { // it's a duplicate
// TO DO - interpolate duplicates in rc.c for frsky so that incoming steps don't have them
pidRuntime.angleDuplicateCount[axis] += 1;
const float rcDeflectionAbs = getRcDeflectionAbs(axis);
if (pidRuntime.angleDuplicateCount[axis] == 1 && rcDeflectionAbs < 0.97f) {
// on first duplicate, unless we just hit max deflection, reduce glitch by interpolation
angleFeedforwardInput = pidRuntime.angleTargetDelta[axis];
} else {
// force feedforward to zero
pidRuntime.angleDuplicateCount[axis] = 2;
pidRuntime.angleTargetDelta[axis] = 0.0f;
angleFeedforwardInput = 0.0f;
}
}
// jitter attenuation copied from feedforward.c
// TO DO move jitter algorithm to rc.c and use same code here and in feedforward.c
const float feedforwardJitterFactor = pidRuntime.feedforwardJitterFactor;
float jitterAttenuator = 1.0f;
if (feedforwardJitterFactor && rcCommandDeltaAbs < feedforwardJitterFactor) {
jitterAttenuator = 1.0f - (rcCommandDeltaAbs / feedforwardJitterFactor);
jitterAttenuator = 1.0f - jitterAttenuator * jitterAttenuator;
}
angleFeedforwardInput *= jitterAttenuator * rxRateHz;
pidRuntime.angleFeedforward[axis] = angleFeedforwardInput; // feedforward element in degrees
}
return currentPidSetpoint;
angleFeedforward = pidRuntime.angleFeedforward[axis] * pidRuntime.angleFeedforwardGain;
// filter angle feedforward, heavily, at the PID loop rate, providing user control over time constant
angleFeedforward = pt3FilterApply(&pidRuntime.angleFeedforwardPt3[axis], angleFeedforward);
#endif // USE_FEEDFORWARD
// calculate error angle and limit the angle to the max inclination
// stick input is from rcCommand, is smoothed, includes level expo, and is in range [-1.0, 1.0]
float angleTarget = angleLimit * getAngleModeStickInputRaw(axis);
#ifdef USE_GPS_RESCUE
angleTarget += gpsRescueAngle[axis] / 100.0f; // Angle is in centidegrees, stepped on roll at 10Hz but not on pitch
#endif
const float currentAngle = (attitude.raw[axis] - angleTrim->raw[axis]) / 10.0f; // stepped at 500hz with some 4ms flat spots
const float errorAngle = angleTarget - currentAngle;
float angleRate = errorAngle * pidRuntime.angleGain + angleFeedforward;
// optionally, minimise cross-axis wobble due to faster yaw responses than roll or pitch, and make co-ordinated yaw turns
// by compensating for the effect of yaw on roll while pitched, and on pitch while rolled
float axisCoordination = pidRuntime.angleYawSetpoint;
if (pidRuntime.angleEarthRef) {
const float sinAngle = sin_approx(DEGREES_TO_RADIANS(pidRuntime.angleTarget[axis == FD_ROLL ? FD_PITCH : FD_ROLL]));
pidRuntime.angleTarget[axis] = angleTarget; // store target for alternate axis to current axis, for use in preceding calculation
axisCoordination *= (axis == FD_ROLL) ? -sinAngle : sinAngle; // must be negative for Roll
angleRate += axisCoordination * pidRuntime.angleEarthRef;
}
// smooth final angle rate output to clean up attitude signal steps (500hz), GPS steps (10 or 100hz), RC steps etc
// this filter runs at ATTITUDE_CUTOFF_HZ, currently 50hz, so GPS roll may be a bit steppy
angleRate = pt3FilterApply(&pidRuntime.attitudeFilter[axis], angleRate);
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(GPS_RESCUE_MODE)) {
rawSetpoint = angleRate;
} else {
// can only be HORIZON mode - crossfade Angle rate and Acro rate
rawSetpoint = rawSetpoint * (1.0f - horizonLevelStrength) + angleRate * horizonLevelStrength;
}
//logging
if (axis == FD_ROLL) {
DEBUG_SET(DEBUG_ANGLE_MODE, 0, lrintf(angleTarget * 10.0f)); // target angle
DEBUG_SET(DEBUG_ANGLE_MODE, 1, lrintf(errorAngle * pidRuntime.angleGain * 10.0f)); // un-smoothed error correction in degrees
DEBUG_SET(DEBUG_ANGLE_MODE, 2, lrintf(angleFeedforward * 10.0f)); // feedforward amount in degrees
DEBUG_SET(DEBUG_ANGLE_MODE, 3, lrintf(currentAngle * 10.0f)); // angle returned
DEBUG_SET(DEBUG_ANGLE_TARGET, 0, lrintf(angleTarget * 10.0f));
DEBUG_SET(DEBUG_ANGLE_TARGET, 1, lrintf(axisCoordination * 10.0f));
// debug ANGLE_TARGET 2 is yaw attenuation
DEBUG_SET(DEBUG_ANGLE_TARGET, 3, lrintf(currentAngle * 10.0f)); // angle returned
}
DEBUG_SET(DEBUG_CURRENT_ANGLE, axis, lrintf(currentAngle * 10.0f)); // current angle
return rawSetpoint;
}
static FAST_CODE_NOINLINE void handleCrashRecovery(
@ -476,7 +519,7 @@ static FAST_CODE_NOINLINE void handleCrashRecovery(
if (sensors(SENSOR_ACC)) {
// errorAngle is deviation from horizontal
const float errorAngle = -(attitude.raw[axis] - angleTrim->raw[axis]) / 10.0f;
*currentPidSetpoint = errorAngle * pidRuntime.levelGain;
*currentPidSetpoint = errorAngle * pidRuntime.angleGain;
*errorRate = *currentPidSetpoint - gyroRate;
}
}
@ -732,7 +775,11 @@ STATIC_UNIT_TESTED void applyItermRelax(const int axis, const float iterm,
if (pidRuntime.itermRelax) {
if (axis < FD_YAW || pidRuntime.itermRelax == ITERM_RELAX_RPY || pidRuntime.itermRelax == ITERM_RELAX_RPY_INC) {
const float itermRelaxFactor = MAX(0, 1 - setpointHpf / ITERM_RELAX_SETPOINT_THRESHOLD);
float itermRelaxThreshold = ITERM_RELAX_SETPOINT_THRESHOLD;
if (FLIGHT_MODE(ANGLE_MODE)) {
itermRelaxThreshold *= 0.2f;
}
const float itermRelaxFactor = MAX(0, 1 - setpointHpf / itermRelaxThreshold);
const bool isDecreasingI =
((iterm > 0) && (*itermErrorRate < 0)) || ((iterm < 0) && (*itermErrorRate > 0));
if ((pidRuntime.itermRelax >= ITERM_RELAX_RP_INC) && isDecreasingI) {
@ -932,23 +979,42 @@ void FAST_CODE pidController(const pidProfile_t *pidProfile, timeUs_t currentTim
rpmFilterUpdate();
#endif
#ifdef USE_FEEDFORWARD
const bool newRcFrame = getShouldUpdateFeedforward();
#endif
const bool newRcFrame = getShouldUpdateFeedforward();
// ----------PID controller----------
for (int axis = FD_ROLL; axis <= FD_YAW; ++axis) {
float currentPidSetpoint = getSetpointRate(axis);
float rawSetpoint = getRawSetpoint(axis);
bool rawSetpointIsSmoothed = false;
if (pidRuntime.maxVelocity[axis]) {
currentPidSetpoint = accelerationLimit(axis, currentPidSetpoint);
}
// Yaw control is GYRO based, direct sticks control is applied to rate PID
// When Race Mode is active PITCH control is also GYRO based in level or horizon mode
#if defined(USE_ACC)
// earth reference yaw by attenuating yaw rate at higher angles
if (axis == FD_YAW && pidRuntime.angleEarthRef) {
pidRuntime.angleYawSetpoint = currentPidSetpoint;
if (levelMode == LEVEL_MODE_RP) {
float maxAngleTargetAbs = fmaxf( fabsf(pidRuntime.angleTarget[FD_ROLL]), fabsf(pidRuntime.angleTarget[FD_PITCH]) );
maxAngleTargetAbs *= pidRuntime.angleEarthRef;
if (FLIGHT_MODE(HORIZON_MODE)) {
// reduce yaw compensation when Horizon uses less levelling
maxAngleTargetAbs *= horizonLevelStrength;
}
float attenuateYawSetpoint = cos_approx(DEGREES_TO_RADIANS(maxAngleTargetAbs));
currentPidSetpoint *= attenuateYawSetpoint;
rawSetpoint *= attenuateYawSetpoint;
DEBUG_SET(DEBUG_ANGLE_TARGET, 2, lrintf(attenuateYawSetpoint * 100.0f)); // yaw attenuation
}
}
if ((levelMode == LEVEL_MODE_R && axis == FD_ROLL)
|| (levelMode == LEVEL_MODE_RP && (axis == FD_ROLL || axis == FD_PITCH)) ) {
currentPidSetpoint = pidLevel(axis, pidProfile, angleTrim, currentPidSetpoint, horizonLevelStrength);
rawSetpoint = pidLevel(axis, pidProfile, angleTrim, rawSetpoint, horizonLevelStrength, newRcFrame);
currentPidSetpoint = rawSetpoint;
rawSetpointIsSmoothed = true;
// levelled axes are already smoothed; feedforward should be calculated each PID loop
DEBUG_SET(DEBUG_ATTITUDE, axis - FD_ROLL + 2, currentPidSetpoint);
}
#endif
@ -1031,7 +1097,7 @@ void FAST_CODE pidController(const pidProfile_t *pidProfile, timeUs_t currentTim
// -----calculate pidSetpointDelta
float pidSetpointDelta = 0;
#ifdef USE_FEEDFORWARD
pidSetpointDelta = feedforwardApply(axis, newRcFrame, pidRuntime.feedforwardAveraging);
pidSetpointDelta = feedforwardApply(axis, newRcFrame, pidRuntime.feedforwardAveraging, rawSetpoint, rawSetpointIsSmoothed);
#endif
pidRuntime.previousPidSetpoint[axis] = currentPidSetpoint;
@ -1103,8 +1169,6 @@ void FAST_CODE pidController(const pidProfile_t *pidProfile, timeUs_t currentTim
// no feedforward in launch control
float feedforwardGain = launchControlActive ? 0.0f : pidRuntime.pidCoefficient[axis].Kf;
if (feedforwardGain > 0) {
// halve feedforward in Level mode since stick sensitivity is weaker by about half
feedforwardGain *= FLIGHT_MODE(ANGLE_MODE) ? 0.5f : 1.0f;
// transition now calculated in feedforward.c when new RC data arrives
float feedForward = feedforwardGain * pidSetpointDelta * pidRuntime.pidFrequency;