Merge pull request #2550 from martinbudden/bf_pidsum_limit_yaw

Added separate yaw pidsum limit
This commit is contained in:
borisbstyle 2017-03-07 12:57:20 +01:00 committed by GitHub
commit 58d2432f1f
8 changed files with 12 additions and 16 deletions

View File

@ -1280,7 +1280,6 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz:%d", currentPidProfile->dterm_notch_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz:%d", currentPidProfile->dterm_notch_hz);
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff:%d", currentPidProfile->dterm_notch_cutoff); BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff:%d", currentPidProfile->dterm_notch_cutoff);
BLACKBOX_PRINT_HEADER_LINE("itermWindupPointPercent:%d", currentPidProfile->itermWindupPointPercent); BLACKBOX_PRINT_HEADER_LINE("itermWindupPointPercent:%d", currentPidProfile->itermWindupPointPercent);
BLACKBOX_PRINT_HEADER_LINE("yaw_p_limit:%d", currentPidProfile->yaw_p_limit);
BLACKBOX_PRINT_HEADER_LINE("dterm_average_count:%d", currentPidProfile->dterm_average_count); BLACKBOX_PRINT_HEADER_LINE("dterm_average_count:%d", currentPidProfile->dterm_average_count);
BLACKBOX_PRINT_HEADER_LINE("vbat_pid_compensation:%d", currentPidProfile->vbatPidCompensation); BLACKBOX_PRINT_HEADER_LINE("vbat_pid_compensation:%d", currentPidProfile->vbatPidCompensation);
BLACKBOX_PRINT_HEADER_LINE("pidAtMinThrottle:%d", currentPidProfile->pidAtMinThrottle); BLACKBOX_PRINT_HEADER_LINE("pidAtMinThrottle:%d", currentPidProfile->pidAtMinThrottle);
@ -1292,6 +1291,8 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("dtermSetpointWeight:%d", currentPidProfile->dtermSetpointWeight); BLACKBOX_PRINT_HEADER_LINE("dtermSetpointWeight:%d", currentPidProfile->dtermSetpointWeight);
BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit:%d", castFloatBytesToInt(currentPidProfile->yawRateAccelLimit)); BLACKBOX_PRINT_HEADER_LINE("yawRateAccelLimit:%d", castFloatBytesToInt(currentPidProfile->yawRateAccelLimit));
BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", castFloatBytesToInt(currentPidProfile->rateAccelLimit)); BLACKBOX_PRINT_HEADER_LINE("rateAccelLimit:%d", castFloatBytesToInt(currentPidProfile->rateAccelLimit));
BLACKBOX_PRINT_HEADER_LINE("pidSumLimit:%d", castFloatBytesToInt(currentPidProfile->pidSumLimit));
BLACKBOX_PRINT_HEADER_LINE("pidSumLimitYaw:%d", castFloatBytesToInt(currentPidProfile->pidSumLimitYaw));
// 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);

View File

@ -343,7 +343,6 @@ static uint16_t cmsx_dterm_lpf_hz;
static uint16_t cmsx_dterm_notch_hz; static uint16_t cmsx_dterm_notch_hz;
static uint16_t cmsx_dterm_notch_cutoff; static uint16_t cmsx_dterm_notch_cutoff;
static uint16_t cmsx_yaw_lpf_hz; static uint16_t cmsx_yaw_lpf_hz;
static uint16_t cmsx_yaw_p_limit;
static long cmsx_FilterPerProfileRead(void) static long cmsx_FilterPerProfileRead(void)
{ {
@ -352,7 +351,6 @@ static long cmsx_FilterPerProfileRead(void)
cmsx_dterm_notch_hz = pidProfile->dterm_notch_hz; cmsx_dterm_notch_hz = pidProfile->dterm_notch_hz;
cmsx_dterm_notch_cutoff = pidProfile->dterm_notch_cutoff; cmsx_dterm_notch_cutoff = pidProfile->dterm_notch_cutoff;
cmsx_yaw_lpf_hz = pidProfile->yaw_lpf_hz; cmsx_yaw_lpf_hz = pidProfile->yaw_lpf_hz;
cmsx_yaw_p_limit = pidProfile->yaw_p_limit;
return 0; return 0;
} }
@ -366,7 +364,6 @@ static long cmsx_FilterPerProfileWriteback(const OSD_Entry *self)
pidProfile->dterm_notch_hz = cmsx_dterm_notch_hz; pidProfile->dterm_notch_hz = cmsx_dterm_notch_hz;
pidProfile->dterm_notch_cutoff = cmsx_dterm_notch_cutoff; pidProfile->dterm_notch_cutoff = cmsx_dterm_notch_cutoff;
pidProfile->yaw_lpf_hz = cmsx_yaw_lpf_hz; pidProfile->yaw_lpf_hz = cmsx_yaw_lpf_hz;
pidProfile->yaw_p_limit = cmsx_yaw_p_limit;
return 0; return 0;
} }
@ -379,7 +376,6 @@ static OSD_Entry cmsx_menuFilterPerProfileEntries[] =
{ "DTERM NF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_hz, 0, 500, 1 }, 0 }, { "DTERM NF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_hz, 0, 500, 1 }, 0 },
{ "DTERM NFCO", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_cutoff, 0, 500, 1 }, 0 }, { "DTERM NFCO", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_cutoff, 0, 500, 1 }, 0 },
{ "YAW LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_yaw_lpf_hz, 0, 500, 1 }, 0 }, { "YAW LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_yaw_lpf_hz, 0, 500, 1 }, 0 },
{ "YAW P LIM", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_yaw_p_limit, 100, 500, 1 }, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 }, { "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 } { NULL, OME_END, NULL, NULL, 0 }

View File

@ -1021,8 +1021,8 @@ static const clivalue_t valueTable[] = {
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &rcControlsConfig()->yaw_control_direction, .config.minmax = { -1, 1 } }, { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &rcControlsConfig()->yaw_control_direction, .config.minmax = { -1, 1 } },
{ "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, &pidProfiles(0)->yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
{ "pidsum_limit", VAR_FLOAT | PROFILE_VALUE, &pidProfiles(0)->pidSumLimit, .config.minmax = { 0.1, 1.0 } }, { "pidsum_limit", VAR_FLOAT | PROFILE_VALUE, &pidProfiles(0)->pidSumLimit, .config.minmax = { 0.1, 1.0 } },
{ "pidsum_limit_yaw", VAR_FLOAT | PROFILE_VALUE, &pidProfiles(0)->pidSumLimitYaw, .config.minmax = { 0.1, 1.0 } },
#ifdef USE_SERVOS #ifdef USE_SERVOS
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->dev.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->dev.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } }, { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },

View File

@ -230,8 +230,8 @@ void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->I8[PIDVEL] = 55; pidProfile->I8[PIDVEL] = 55;
pidProfile->D8[PIDVEL] = 75; pidProfile->D8[PIDVEL] = 75;
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->pidSumLimit = PIDSUM_LIMIT; pidProfile->pidSumLimit = PIDSUM_LIMIT;
pidProfile->pidSumLimitYaw = PIDSUM_LIMIT_YAW;
pidProfile->yaw_lpf_hz = 0; pidProfile->yaw_lpf_hz = 0;
pidProfile->itermWindupPointPercent = 50; pidProfile->itermWindupPointPercent = 50;
pidProfile->dterm_filter_type = FILTER_BIQUAD; pidProfile->dterm_filter_type = FILTER_BIQUAD;

View File

@ -1150,7 +1150,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
case MSP_PID_ADVANCED: case MSP_PID_ADVANCED:
sbufWriteU16(dst, 0); sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0); sbufWriteU16(dst, 0);
sbufWriteU16(dst, currentPidProfile->yaw_p_limit); sbufWriteU16(dst, 0); // was pidProfile.yaw_p_limit
sbufWriteU8(dst, 0); // reserved sbufWriteU8(dst, 0); // reserved
sbufWriteU8(dst, currentPidProfile->vbatPidCompensation); sbufWriteU8(dst, currentPidProfile->vbatPidCompensation);
sbufWriteU8(dst, currentPidProfile->setpointRelaxRatio); sbufWriteU8(dst, currentPidProfile->setpointRelaxRatio);
@ -1540,7 +1540,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_PID_ADVANCED: case MSP_SET_PID_ADVANCED:
sbufReadU16(src); sbufReadU16(src);
sbufReadU16(src); sbufReadU16(src);
currentPidProfile->yaw_p_limit = sbufReadU16(src); sbufReadU16(src); // was pidProfile.yaw_p_limit
sbufReadU8(src); // reserved sbufReadU8(src); // reserved
currentPidProfile->vbatPidCompensation = sbufReadU8(src); currentPidProfile->vbatPidCompensation = sbufReadU8(src);
currentPidProfile->setpointRelaxRatio = sbufReadU8(src); currentPidProfile->setpointRelaxRatio = sbufReadU8(src);

View File

@ -516,9 +516,9 @@ void mixTable(pidProfile_t *pidProfile)
float scaledAxisPIDf[3]; float scaledAxisPIDf[3];
// Limit the PIDsum // Limit the PIDsum
for (int axis = 0; axis < 3; axis++) { scaledAxisPIDf[FD_ROLL] = constrainf(axisPIDf[FD_ROLL] / PID_MIXER_SCALING, -pidProfile->pidSumLimit, pidProfile->pidSumLimit);
scaledAxisPIDf[axis] = constrainf(axisPIDf[axis] / PID_MIXER_SCALING, -pidProfile->pidSumLimit, pidProfile->pidSumLimit); scaledAxisPIDf[FD_PITCH] = constrainf(axisPIDf[FD_PITCH] / PID_MIXER_SCALING, -pidProfile->pidSumLimit, pidProfile->pidSumLimit);
} scaledAxisPIDf[FD_YAW] = constrainf(axisPIDf[FD_YAW] / PID_MIXER_SCALING, -pidProfile->pidSumLimit, pidProfile->pidSumLimitYaw);
// Calculate voltage compensation // Calculate voltage compensation
const float vbatCompensationFactor = pidProfile->vbatPidCompensation ? calculateVbatPidCompensation() : 1.0f; const float vbatCompensationFactor = pidProfile->vbatPidCompensation ? calculateVbatPidCompensation() : 1.0f;

View File

@ -109,8 +109,8 @@ void resetPidProfile(pidProfile_t *pidProfile)
.I8[PIDVEL] = 55, .I8[PIDVEL] = 55,
.D8[PIDVEL] = 75, .D8[PIDVEL] = 75,
.yaw_p_limit = YAW_P_LIMIT_MAX,
.pidSumLimit = PIDSUM_LIMIT, .pidSumLimit = PIDSUM_LIMIT,
.pidSumLimitYaw = PIDSUM_LIMIT_YAW,
.yaw_lpf_hz = 0, .yaw_lpf_hz = 0,
.itermWindupPointPercent = 50, .itermWindupPointPercent = 50,
.dterm_filter_type = FILTER_BIQUAD, .dterm_filter_type = FILTER_BIQUAD,

View File

@ -24,9 +24,8 @@
#define PID_CONTROLLER_BETAFLIGHT 1 #define PID_CONTROLLER_BETAFLIGHT 1
#define PID_MIXER_SCALING 1000.0f #define PID_MIXER_SCALING 1000.0f
#define PID_SERVO_MIXER_SCALING 0.7f #define PID_SERVO_MIXER_SCALING 0.7f
#define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter
#define YAW_P_LIMIT_MAX 500 // Maximum value for yaw P limiter
#define PIDSUM_LIMIT 0.5f #define PIDSUM_LIMIT 0.5f
#define PIDSUM_LIMIT_YAW 0.4f
// Scaling factors for Pids for better tunable range in configurator for betaflight pid controller. The scaling is based on legacy pid controller or previous float // Scaling factors for Pids for better tunable range in configurator for betaflight pid controller. The scaling is based on legacy pid controller or previous float
#define PTERM_SCALE 0.032029f #define PTERM_SCALE 0.032029f
@ -69,8 +68,8 @@ typedef struct pidProfile_s {
uint16_t dterm_notch_hz; // Biquad dterm notch hz uint16_t dterm_notch_hz; // Biquad dterm notch hz
uint16_t dterm_notch_cutoff; // Biquad dterm notch low cutoff uint16_t dterm_notch_cutoff; // Biquad dterm notch low cutoff
uint8_t itermWindupPointPercent; // Experimental ITerm windup threshold, percent motor saturation uint8_t itermWindupPointPercent; // Experimental ITerm windup threshold, percent motor saturation
uint16_t yaw_p_limit;
float pidSumLimit; float pidSumLimit;
float pidSumLimitYaw;
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.