mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 23:05:19 +03:00
Add rc_rate_yaw // SuperExpo feature renamed to SUPEREXPO_RATES
This commit is contained in:
parent
6c8a8614fc
commit
a74acccb84
9 changed files with 15 additions and 19 deletions
|
@ -80,14 +80,14 @@ float calculateRate(int axis, const controlRateConfig_t *controlRateConfig) {
|
|||
|
||||
if (isSuperExpoActive()) {
|
||||
float rcFactor = (axis == YAW) ? (ABS(rcCommand[axis]) / 500.0f) : (ABS(rcCommand[axis]) / (500.0f * (controlRateConfig->rcRate8 / 100.0f)));
|
||||
rcFactor = constrainf(1.0f / (1.0f - (rcFactor * (controlRateConfig->rates[axis] / 100.0f))), 0.01f, 1.00f);
|
||||
rcFactor = 1.0f / (constrainf(1.0f - (rcFactor * (controlRateConfig->rates[axis] / 100.0f)), 0.01f, 1.00f));
|
||||
|
||||
angleRate = rcFactor * ((27 * rcCommand[axis]) / 16.0f);
|
||||
} else {
|
||||
angleRate = (float)((controlRateConfig->rates[axis] + 27) * rcCommand[axis]) / 16.0f;
|
||||
}
|
||||
|
||||
return constrainf(angleRate, -8190, 8290); // Rate limit protection
|
||||
return constrainf(angleRate, -8190.0f, 8190.0f); // Rate limit protection
|
||||
}
|
||||
|
||||
uint16_t getDynamicKp(int axis, const pidProfile_t *pidProfile) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue