From 1030df294db41bb418aa43eb756d2f9e10f0cbc5 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Fri, 30 Dec 2016 12:04:44 +0100 Subject: [PATCH] PID code cleanup // refactoring --- src/main/blackbox/blackbox.c | 4 +- src/main/fc/config.c | 6 +- src/main/fc/fc_main.c | 29 +++++--- src/main/fc/fc_main.h | 3 + src/main/fc/fc_msp.c | 8 +-- src/main/flight/pid.c | 130 +++++++++++++++++++---------------- src/main/flight/pid.h | 8 +-- src/main/io/serial_cli.c | 8 +-- 8 files changed, 110 insertions(+), 86 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index e9aeae311..33a0fb8a7 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1261,8 +1261,8 @@ static bool blackboxWriteSysinfo() BLACKBOX_PRINT_HEADER_LINE("itermThrottleThreshold:%d", currentProfile->pidProfile.itermThrottleThreshold); BLACKBOX_PRINT_HEADER_LINE("setpointRelaxRatio:%d", currentProfile->pidProfile.setpointRelaxRatio); BLACKBOX_PRINT_HEADER_LINE("dtermSetpointWeight:%d", currentProfile->pidProfile.dtermSetpointWeight); - BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit:%d", currentProfile->pidProfile.yawRateAccelLimit); - BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", currentProfile->pidProfile.rateAccelLimit); + BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit:%d", castFloatBytesToInt(currentProfile->pidProfile.yawRateAccelLimit)); + BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", castFloatBytesToInt(currentProfile->pidProfile.rateAccelLimit)); // End of Betaflight controller parameters BLACKBOX_PRINT_HEADER_LINE("deadband:%d", rcControlsConfig()->deadband); diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 7b776524d..a2837d98a 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -176,12 +176,13 @@ static void resetPidProfile(pidProfile_t *pidProfile) pidProfile->dterm_notch_cutoff = 160; pidProfile->vbatPidCompensation = 0; pidProfile->pidAtMinThrottle = PID_STABILISATION_ON; + pidProfile->max_angle_inclination = 70.0f; // 70 degrees // Betaflight PID controller parameters pidProfile->setpointRelaxRatio = 30; pidProfile->dtermSetpointWeight = 200; - pidProfile->yawRateAccelLimit = 220; - pidProfile->rateAccelLimit = 0; + pidProfile->yawRateAccelLimit = 20.0f; + pidProfile->rateAccelLimit = 0.0f; pidProfile->itermThrottleThreshold = 350; pidProfile->levelSensitivity = 2.0f; } @@ -612,7 +613,6 @@ void createDefaultConfig(master_t *config) config->gyroConfig.gyro_sync_denom = 4; config->pidConfig.pid_process_denom = 2; #endif - config->pidConfig.max_angle_inclination = 700; // 70 degrees config->gyroConfig.gyro_soft_lpf_type = FILTER_PT1; config->gyroConfig.gyro_soft_lpf_hz = 90; config->gyroConfig.gyro_soft_notch_hz_1 = 400; diff --git a/src/main/fc/fc_main.c b/src/main/fc/fc_main.c index 7e2412462..5aca65f7d 100644 --- a/src/main/fc/fc_main.c +++ b/src/main/fc/fc_main.c @@ -92,13 +92,25 @@ uint8_t motorControlEnable = false; 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 -extern uint8_t PIDweight[3]; +static float throttlePIDAttenuation; uint16_t filteredCycleTime; bool isRXDataNew; static bool armingCalibrationWasInitialised; -float setpointRate[3]; -float rcInput[3]; +static float setpointRate[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) { @@ -137,11 +149,11 @@ void calculateSetpointRate(int axis, int16_t rc) { if (rcRate > 2.0f) rcRate = rcRate + (RC_RATE_INCREMENTAL * (rcRate - 2.0f)); rcCommandf = rc / 500.0f; - rcInput[axis] = ABS(rcCommandf); + rcDeflection[axis] = ABS(rcCommandf); if (rcExpo) { 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; @@ -270,17 +282,18 @@ void updateRcCommands(void) int32_t prop; if (rcData[THROTTLE] < currentControlRateProfile->tpa_breakpoint) { prop = 100; + throttlePIDAttenuation = 1.0f; } else { if (rcData[THROTTLE] < 2000) { prop = 100 - (uint16_t)currentControlRateProfile->dynThrPID * (rcData[THROTTLE] - currentControlRateProfile->tpa_breakpoint) / (2000 - currentControlRateProfile->tpa_breakpoint); } else { prop = 100 - currentControlRateProfile->dynThrPID; } + throttlePIDAttenuation = prop / 100.0f; } for (int axis = 0; axis < 3; axis++) { // 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); if (axis == ROLL || axis == PITCH) { @@ -679,9 +692,7 @@ void subTaskPidController(void) // PID - note this is function pointer set by setPIDController() pidController( ¤tProfile->pidProfile, - pidConfig()->max_angle_inclination, - &accelerometerConfig()->accelerometerTrims, - rxConfig()->midrc + &accelerometerConfig()->accelerometerTrims ); if (debugMode == DEBUG_PIDLOOP || debugMode == DEBUG_SCHEDULER) {debug[1] = micros() - startTime;} } diff --git a/src/main/fc/fc_main.h b/src/main/fc/fc_main.h index 27c568024..c44300b85 100644 --- a/src/main/fc/fc_main.h +++ b/src/main/fc/fc_main.h @@ -34,3 +34,6 @@ void updateLEDs(void); void updateRcCommands(void); void taskMainPidLoop(timeUs_t currentTimeUs); +float getThrottlePIDAttenuation(void); +float getSetpointRate(int axis); +float getRcDeflection(int axis); diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 31b0ac1d2..5c14903d2 100755 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -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 - sbufWriteU16(dst, currentProfile->pidProfile.rateAccelLimit); - sbufWriteU16(dst, currentProfile->pidProfile.yawRateAccelLimit); + sbufWriteU16(dst, currentProfile->pidProfile.rateAccelLimit * 10); + sbufWriteU16(dst, currentProfile->pidProfile.yawRateAccelLimit * 10); break; 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 - currentProfile->pidProfile.rateAccelLimit = sbufReadU16(src); - currentProfile->pidProfile.yawRateAccelLimit = sbufReadU16(src); + currentProfile->pidProfile.rateAccelLimit = sbufReadU16(src) / 10.0f; + currentProfile->pidProfile.yawRateAccelLimit = sbufReadU16(src) / 10.0f; pidInitConfig(¤tProfile->pidProfile); break; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index dae5507ba..6e52c24d8 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -28,6 +28,7 @@ #include "common/maths.h" #include "common/filter.h" +#include "fc/fc_main.h" #include "fc/rc_controls.h" #include "fc/runtime_config.h" @@ -38,17 +39,11 @@ #include "sensors/gyro.h" #include "sensors/acceleration.h" -extern float rcInput[3]; -extern float setpointRate[3]; - uint32_t targetPidLooptime; static bool pidStabilisationEnabled; 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 int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; #endif @@ -145,8 +140,7 @@ void pidInitFilters(const pidProfile_t *pidProfile) } } -static float Kp[3], Ki[3], Kd[3], c[3]; -static float rollPitchMaxVelocity, yawMaxVelocity, relaxFactor[3]; +static float Kp[3], Ki[3], Kd[3], c[3], levelGain, horizonGain, horizonTransition, maxVelocity[3], relaxFactor[3]; void pidInitConfig(const pidProfile_t *pidProfile) { 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; relaxFactor[axis] = 1.0f - (pidProfile->setpointRelaxRatio / 100.0f); } - yawMaxVelocity = pidProfile->yawRateAccelLimit * 1000 * dT; - rollPitchMaxVelocity = pidProfile->rateAccelLimit * 1000 * dT; + levelGain = pidProfile->P8[PIDLEVEL] / 10.0f; + 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; +} + +float currentPidSetpoint = 0, horizonLevelStrength = 1.0f; + +void calcHorizonLevelStrength(const pidProfile_t *pidProfile) { + const float mostDeflectedPos = MAX(getRcDeflection(FD_ROLL), getRcDeflection(FD_PITCH)); + // Progressively turn off the horizon self level strength as the stick is banged over + horizonLevelStrength = (1.0f - mostDeflectedPos); // 1 at centre stick, 0 = max stick deflection + if(pidProfile->D8[PIDLEVEL] == 0){ + horizonLevelStrength = 0; + } else { + horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * horizonTransition) + 1, 0, 1); + } +} + +void pidLevel(int axis, const pidProfile_t *pidProfile, const rollAndPitchTrims_t *angleTrim) { + // calculate error angle and limit the angle to the max inclination + float errorAngle = pidProfile->levelSensitivity * rcCommand[axis]; +#ifdef GPS + errorAngle += GPS_angle[axis]; +#endif + errorAngle = constrainf(errorAngle, -pidProfile->max_angle_inclination, pidProfile->max_angle_inclination); + errorAngle = (errorAngle - ((attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f)); + if(FLIGHT_MODE(ANGLE_MODE)) { + // ANGLE mode - control is angle based, so control loop is needed + currentPidSetpoint = errorAngle * levelGain; + } else { + // HORIZON mode - direct sticks control is applied to rate PID + // mix up angle error to desired AngleRate to add a little auto-level feel + 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, uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, uint16_t midrc) +void pidController(const pidProfile_t *pidProfile, const rollAndPitchTrims_t *angleTrim) { static float previousRateError[2]; static float previousSetpoint[3]; - float horizonLevelStrength = 1; - if (FLIGHT_MODE(HORIZON_MODE)) { - // 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 - horizonLevelStrength = (float)(500 - mostDeflectedPos) / 500; // 1 at centre stick, 0 = max stick deflection - if(pidProfile->D8[PIDLEVEL] == 0){ - horizonLevelStrength = 0; - } else { - horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * (100 / pidProfile->D8[PIDLEVEL])) + 1, 0, 1); - } - } + if(FLIGHT_MODE(HORIZON_MODE)) + calcHorizonLevelStrength(pidProfile); // ----------PID controller---------- - const float tpaFactor = PIDweight[0] / 100.0f; // tpa is now float + const float tpaFactor = getThrottlePIDAttenuation(); + 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; - } - } + 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) { - // calculate error angle and limit the angle to the max inclination - float errorAngle = pidProfile->levelSensitivity * rcCommand[axis]; -#ifdef GPS - errorAngle += GPS_angle[axis]; -#endif - errorAngle = constrainf(errorAngle, -max_angle_inclination, max_angle_inclination); - errorAngle = (errorAngle - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f; - if (FLIGHT_MODE(ANGLE_MODE)) { - // ANGLE mode - control is angle based, so control loop is needed - setpointRate[axis] = errorAngle * pidProfile->P8[PIDLEVEL] / 10.0f; - } else { - // HORIZON mode - direct sticks control is applied to rate PID - // 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); - } + 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. ---------- // ---------- 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 - 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 float PTerm = Kp[axis] * errorRate * tpaFactor; @@ -227,7 +236,7 @@ void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio // -----calculate I component // Reduce strong Iterm accumulation during higher stick inputs 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]; 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) { float dynC = c[axis]; if (pidProfile->setpointRelaxRatio < 100) { + const float rcDeflection = getRcDeflection(axis); dynC = c[axis]; - if (setpointRate[axis] > 0) { - if ((setpointRate[axis] - previousSetpoint[axis]) < previousSetpoint[axis]) - dynC = dynC * sq(rcInput[axis]) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]); - } else if (setpointRate[axis] < 0) { - if ((setpointRate[axis] - previousSetpoint[axis]) > previousSetpoint[axis]) - dynC = dynC * sq(rcInput[axis]) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]); + if (currentPidSetpoint > 0) { + if ((currentPidSetpoint - previousSetpoint[axis]) < previousSetpoint[axis]) + dynC = dynC * sq(rcDeflection) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]); + } else if (currentPidSetpoint < 0) { + if ((currentPidSetpoint - previousSetpoint[axis]) > previousSetpoint[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) const float delta = (rD - previousRateError[axis]) / dT; previousRateError[axis] = rD; @@ -264,7 +274,7 @@ void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio } else { PTerm = ptermYawFilterApplyFn(ptermYawFilter, PTerm); } - previousSetpoint[axis] = setpointRate[axis]; + previousSetpoint[axis] = currentPidSetpoint; // -----calculate total PID output axisPIDf[axis] = PTerm + ITerm + DTerm; diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index c108c8b78..171c261a7 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -72,23 +72,23 @@ typedef struct pidProfile_s { uint8_t dterm_average_count; // Configurable delta count for dterm 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. + float max_angle_inclination; // Betaflight PID controller parameters uint16_t itermThrottleThreshold; // max allowed throttle delta before errorGyroReset in ms uint8_t setpointRelaxRatio; // Setpoint weight relaxation effect 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 - uint16_t rateAccelLimit; // accel limiter roll/pitch deg/sec/ms + float yawRateAccelLimit; // yaw accel limiter for deg/sec/ms + float rateAccelLimit; // accel limiter roll/pitch deg/sec/ms float levelSensitivity; } pidProfile_t; typedef struct pidConfig_s { uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate - uint16_t max_angle_inclination; } pidConfig_t; 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 int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index c78d61913..c50d0be38 100755 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -835,7 +835,7 @@ const clivalue_t valueTable[] = { { "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 } }, { "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 { "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 } }, @@ -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 } }, { "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 } }, - { "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 } }, { "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 } }, - { "rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rateAccelLimit, .config.minmax = {0, 1000 } }, + { "yaw_accel_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawRateAccelLimit, .config.minmax = {0.1f, 50.0f } }, + { "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 } }, { "yaw_accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },