Merge pull request #3019 from martinbudden/bf_pid_array_rearrange

Rearrange PID array to be array of PIDs
This commit is contained in:
Martin Budden 2017-05-08 08:00:08 +01:00 committed by GitHub
commit 9905186d09
21 changed files with 224 additions and 236 deletions

View File

@ -406,7 +406,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2:
return currentPidProfile->D8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0] != 0;
return currentPidProfile->pid[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0].D != 0;
case FLIGHT_LOG_FIELD_CONDITION_MAG:
#ifdef MAG
@ -1235,34 +1235,34 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE("rates", "%d,%d,%d", currentControlRateProfile->rates[ROLL],
currentControlRateProfile->rates[PITCH],
currentControlRateProfile->rates[YAW]);
BLACKBOX_PRINT_HEADER_LINE("rollPID", "%d,%d,%d", currentPidProfile->P8[ROLL],
currentPidProfile->I8[ROLL],
currentPidProfile->D8[ROLL]);
BLACKBOX_PRINT_HEADER_LINE("pitchPID", "%d,%d,%d", currentPidProfile->P8[PITCH],
currentPidProfile->I8[PITCH],
currentPidProfile->D8[PITCH]);
BLACKBOX_PRINT_HEADER_LINE("yawPID", "%d,%d,%d", currentPidProfile->P8[YAW],
currentPidProfile->I8[YAW],
currentPidProfile->D8[YAW]);
BLACKBOX_PRINT_HEADER_LINE("altPID", "%d,%d,%d", currentPidProfile->P8[PIDALT],
currentPidProfile->I8[PIDALT],
currentPidProfile->D8[PIDALT]);
BLACKBOX_PRINT_HEADER_LINE("posPID", "%d,%d,%d", currentPidProfile->P8[PIDPOS],
currentPidProfile->I8[PIDPOS],
currentPidProfile->D8[PIDPOS]);
BLACKBOX_PRINT_HEADER_LINE("posrPID", "%d,%d,%d", currentPidProfile->P8[PIDPOSR],
currentPidProfile->I8[PIDPOSR],
currentPidProfile->D8[PIDPOSR]);
BLACKBOX_PRINT_HEADER_LINE("navrPID", "%d,%d,%d", currentPidProfile->P8[PIDNAVR],
currentPidProfile->I8[PIDNAVR],
currentPidProfile->D8[PIDNAVR]);
BLACKBOX_PRINT_HEADER_LINE("levelPID", "%d,%d,%d", currentPidProfile->P8[PIDLEVEL],
currentPidProfile->I8[PIDLEVEL],
currentPidProfile->D8[PIDLEVEL]);
BLACKBOX_PRINT_HEADER_LINE("magPID", "%d", currentPidProfile->P8[PIDMAG]);
BLACKBOX_PRINT_HEADER_LINE("velPID", "%d,%d,%d", currentPidProfile->P8[PIDVEL],
currentPidProfile->I8[PIDVEL],
currentPidProfile->D8[PIDVEL]);
BLACKBOX_PRINT_HEADER_LINE("rollPID", "%d,%d,%d", currentPidProfile->pid[PID_ROLL].P,
currentPidProfile->pid[PID_ROLL].I,
currentPidProfile->pid[PID_ROLL].D);
BLACKBOX_PRINT_HEADER_LINE("pitchPID", "%d,%d,%d", currentPidProfile->pid[PID_PITCH].P,
currentPidProfile->pid[PID_PITCH].I,
currentPidProfile->pid[PID_PITCH].D);
BLACKBOX_PRINT_HEADER_LINE("yawPID", "%d,%d,%d", currentPidProfile->pid[PID_YAW].P,
currentPidProfile->pid[PID_YAW].I,
currentPidProfile->pid[PID_YAW].D);
BLACKBOX_PRINT_HEADER_LINE("altPID", "%d,%d,%d", currentPidProfile->pid[PID_ALT].P,
currentPidProfile->pid[PID_ALT].I,
currentPidProfile->pid[PID_ALT].D);
BLACKBOX_PRINT_HEADER_LINE("posPID", "%d,%d,%d", currentPidProfile->pid[PID_POS].P,
currentPidProfile->pid[PID_POS].I,
currentPidProfile->pid[PID_POS].D);
BLACKBOX_PRINT_HEADER_LINE("posrPID", "%d,%d,%d", currentPidProfile->pid[PID_POSR].P,
currentPidProfile->pid[PID_POSR].I,
currentPidProfile->pid[PID_POSR].D);
BLACKBOX_PRINT_HEADER_LINE("navrPID", "%d,%d,%d", currentPidProfile->pid[PID_NAVR].P,
currentPidProfile->pid[PID_NAVR].I,
currentPidProfile->pid[PID_NAVR].D);
BLACKBOX_PRINT_HEADER_LINE("levelPID", "%d,%d,%d", currentPidProfile->pid[PID_LEVEL].P,
currentPidProfile->pid[PID_LEVEL].I,
currentPidProfile->pid[PID_LEVEL].D);
BLACKBOX_PRINT_HEADER_LINE("magPID", "%d", currentPidProfile->pid[PID_MAG].P);
BLACKBOX_PRINT_HEADER_LINE("velPID", "%d,%d,%d", currentPidProfile->pid[PID_VEL].P,
currentPidProfile->pid[PID_VEL].I,
currentPidProfile->pid[PID_VEL].D);
BLACKBOX_PRINT_HEADER_LINE("dterm_filter_type", "%d", currentPidProfile->dterm_filter_type);
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz", "%d", currentPidProfile->dterm_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz", "%d", currentPidProfile->yaw_lpf_hz);

View File

@ -109,9 +109,9 @@ static long cmsx_PidRead(void)
const pidProfile_t *pidProfile = pidProfiles(pidProfileIndex);
for (uint8_t i = 0; i < 3; i++) {
tempPid[i][0] = pidProfile->P8[i];
tempPid[i][1] = pidProfile->I8[i];
tempPid[i][2] = pidProfile->D8[i];
tempPid[i][0] = pidProfile->pid[i].P;
tempPid[i][1] = pidProfile->pid[i].I;
tempPid[i][2] = pidProfile->pid[i].D;
}
return 0;
@ -131,9 +131,9 @@ static long cmsx_PidWriteback(const OSD_Entry *self)
pidProfile_t *pidProfile = currentPidProfile;
for (uint8_t i = 0; i < 3; i++) {
pidProfile->P8[i] = tempPid[i][0];
pidProfile->I8[i] = tempPid[i][1];
pidProfile->D8[i] = tempPid[i][2];
pidProfile->pid[i].P = tempPid[i][0];
pidProfile->pid[i].I = tempPid[i][1];
pidProfile->pid[i].D = tempPid[i][2];
}
pidInitConfig(currentPidProfile);
@ -144,17 +144,17 @@ static OSD_Entry cmsx_menuPidEntries[] =
{
{ "-- PID --", OME_Label, NULL, pidProfileIndexString, 0},
{ "ROLL P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDROLL][0], 0, 200, 1 }, 0 },
{ "ROLL I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDROLL][1], 0, 200, 1 }, 0 },
{ "ROLL D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDROLL][2], 0, 200, 1 }, 0 },
{ "ROLL P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_ROLL][0], 0, 200, 1 }, 0 },
{ "ROLL I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_ROLL][1], 0, 200, 1 }, 0 },
{ "ROLL D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_ROLL][2], 0, 200, 1 }, 0 },
{ "PITCH P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDPITCH][0], 0, 200, 1 }, 0 },
{ "PITCH I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDPITCH][1], 0, 200, 1 }, 0 },
{ "PITCH D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDPITCH][2], 0, 200, 1 }, 0 },
{ "PITCH P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_PITCH][0], 0, 200, 1 }, 0 },
{ "PITCH I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_PITCH][1], 0, 200, 1 }, 0 },
{ "PITCH D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_PITCH][2], 0, 200, 1 }, 0 },
{ "YAW P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDYAW][0], 0, 200, 1 }, 0 },
{ "YAW I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDYAW][1], 0, 200, 1 }, 0 },
{ "YAW D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDYAW][2], 0, 200, 1 }, 0 },
{ "YAW P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_YAW][0], 0, 200, 1 }, 0 },
{ "YAW I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_YAW][1], 0, 200, 1 }, 0 },
{ "YAW D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PID_YAW][2], 0, 200, 1 }, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
@ -242,9 +242,9 @@ static long cmsx_profileOtherOnEnter(void)
cmsx_dtermSetpointWeight = pidProfile->dtermSetpointWeight;
cmsx_setpointRelaxRatio = pidProfile->setpointRelaxRatio;
cmsx_angleStrength = pidProfile->P8[PIDLEVEL];
cmsx_horizonStrength = pidProfile->I8[PIDLEVEL];
cmsx_horizonTransition = pidProfile->D8[PIDLEVEL];
cmsx_angleStrength = pidProfile->pid[PID_LEVEL].P;
cmsx_horizonStrength = pidProfile->pid[PID_LEVEL].I;
cmsx_horizonTransition = pidProfile->pid[PID_LEVEL].D;
return 0;
}
@ -258,9 +258,9 @@ static long cmsx_profileOtherOnExit(const OSD_Entry *self)
pidProfile->setpointRelaxRatio = cmsx_setpointRelaxRatio;
pidInitConfig(currentPidProfile);
pidProfile->P8[PIDLEVEL] = cmsx_angleStrength;
pidProfile->I8[PIDLEVEL] = cmsx_horizonStrength;
pidProfile->D8[PIDLEVEL] = cmsx_horizonTransition;
pidProfile->pid[PID_LEVEL].P = cmsx_angleStrength;
pidProfile->pid[PID_LEVEL].I = cmsx_horizonStrength;
pidProfile->pid[PID_LEVEL].D = cmsx_horizonTransition;
return 0;
}

View File

@ -280,7 +280,7 @@ void updateMagHold(void)
dif -= 360;
dif *= -GET_DIRECTION(rcControlsConfig()->yaw_control_reversed);
if (STATE(SMALL_ANGLE))
rcCommand[YAW] -= dif * currentPidProfile->P8[PIDMAG] / 30; // 18 deg
rcCommand[YAW] -= dif * currentPidProfile->pid[PID_MAG].P / 30; // 18 deg
} else
magHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
}

View File

@ -982,9 +982,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
case MSP_PID:
for (int i = 0; i < PID_ITEM_COUNT; i++) {
sbufWriteU8(dst, currentPidProfile->P8[i]);
sbufWriteU8(dst, currentPidProfile->I8[i]);
sbufWriteU8(dst, currentPidProfile->D8[i]);
sbufWriteU8(dst, currentPidProfile->pid[i].P);
sbufWriteU8(dst, currentPidProfile->pid[i].I);
sbufWriteU8(dst, currentPidProfile->pid[i].D);
}
break;
@ -1445,9 +1445,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_PID:
for (int i = 0; i < PID_ITEM_COUNT; i++) {
currentPidProfile->P8[i] = sbufReadU8(src);
currentPidProfile->I8[i] = sbufReadU8(src);
currentPidProfile->D8[i] = sbufReadU8(src);
currentPidProfile->pid[i].P = sbufReadU8(src);
currentPidProfile->pid[i].I = sbufReadU8(src);
currentPidProfile->pid[i].D = sbufReadU8(src);
}
pidInitConfig(currentPidProfile);
break;

View File

@ -259,8 +259,8 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t
break;
case ADJUSTMENT_PITCH_ROLL_P:
case ADJUSTMENT_PITCH_P:
newValue = constrain((int)pidProfile->P8[PIDPITCH] + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->P8[PIDPITCH] = newValue;
newValue = constrain((int)pidProfile->pid[PID_PITCH].P + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->pid[PID_PITCH].P = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_P, newValue);
if (adjustmentFunction == ADJUSTMENT_PITCH_P) {
@ -268,51 +268,51 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t
}
// follow though for combined ADJUSTMENT_PITCH_ROLL_P
case ADJUSTMENT_ROLL_P:
newValue = constrain((int)pidProfile->P8[PIDROLL] + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->P8[PIDROLL] = newValue;
newValue = constrain((int)pidProfile->pid[PID_ROLL].P + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->pid[PID_ROLL].P = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_ROLL_P, newValue);
break;
case ADJUSTMENT_PITCH_ROLL_I:
case ADJUSTMENT_PITCH_I:
newValue = constrain((int)pidProfile->I8[PIDPITCH] + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->I8[PIDPITCH] = newValue;
newValue = constrain((int)pidProfile->pid[PID_PITCH].I + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->pid[PID_PITCH].I = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_I, newValue);
if (adjustmentFunction == ADJUSTMENT_PITCH_I) {
break;
}
// fall though for combined ADJUSTMENT_PITCH_ROLL_I
case ADJUSTMENT_ROLL_I:
newValue = constrain((int)pidProfile->I8[PIDROLL] + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->I8[PIDROLL] = newValue;
newValue = constrain((int)pidProfile->pid[PID_ROLL].I + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->pid[PID_ROLL].I = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_ROLL_I, newValue);
break;
case ADJUSTMENT_PITCH_ROLL_D:
case ADJUSTMENT_PITCH_D:
newValue = constrain((int)pidProfile->D8[PIDPITCH] + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->D8[PIDPITCH] = newValue;
newValue = constrain((int)pidProfile->pid[PID_PITCH].D + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->pid[PID_PITCH].D = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_D, newValue);
if (adjustmentFunction == ADJUSTMENT_PITCH_D) {
break;
}
// fall though for combined ADJUSTMENT_PITCH_ROLL_D
case ADJUSTMENT_ROLL_D:
newValue = constrain((int)pidProfile->D8[PIDROLL] + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->D8[PIDROLL] = newValue;
newValue = constrain((int)pidProfile->pid[PID_ROLL].D + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->pid[PID_ROLL].D = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_ROLL_D, newValue);
break;
case ADJUSTMENT_YAW_P:
newValue = constrain((int)pidProfile->P8[PIDYAW] + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->P8[PIDYAW] = newValue;
newValue = constrain((int)pidProfile->pid[PID_YAW].P + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->pid[PID_YAW].P = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_YAW_P, newValue);
break;
case ADJUSTMENT_YAW_I:
newValue = constrain((int)pidProfile->I8[PIDYAW] + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->I8[PIDYAW] = newValue;
newValue = constrain((int)pidProfile->pid[PID_YAW].I + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->pid[PID_YAW].I = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_YAW_I, newValue);
break;
case ADJUSTMENT_YAW_D:
newValue = constrain((int)pidProfile->D8[PIDYAW] + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->D8[PIDYAW] = newValue;
newValue = constrain((int)pidProfile->pid[PID_YAW].D + delta, 0, 200); // FIXME magic numbers repeated in cli.c
pidProfile->pid[PID_YAW].D = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_YAW_D, newValue);
break;
case ADJUSTMENT_RC_RATE_YAW:
@ -352,9 +352,9 @@ static void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
case ADJUSTMENT_HORIZON_STRENGTH:
{
uint8_t newValue = constrain(position, 0, 200); // FIXME magic numbers repeated in serial_cli.c
if(pidProfile->D8[PIDLEVEL] != newValue) {
beeps = ((newValue - pidProfile->D8[PIDLEVEL]) / 8) + 1;
pidProfile->D8[PIDLEVEL] = newValue;
if(pidProfile->pid[PID_LEVEL].D != newValue) {
beeps = ((newValue - pidProfile->pid[PID_LEVEL].D) / 8) + 1;
pidProfile->pid[PID_LEVEL].D = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_HORIZON_STRENGTH, position);
}
break;

View File

@ -548,27 +548,27 @@ const clivalue_t valueTable[] = {
{ "pidsum_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 100, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimit) },
{ "pidsum_limit_yaw", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 100, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimitYaw) },
{ "p_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PITCH]) },
{ "i_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PITCH]) },
{ "d_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PITCH]) },
{ "p_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[ROLL]) },
{ "i_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[ROLL]) },
{ "d_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[ROLL]) },
{ "p_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[YAW]) },
{ "i_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[YAW]) },
{ "d_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[YAW]) },
{ "p_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].P) },
{ "i_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].I) },
{ "d_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].D) },
{ "p_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_ROLL].P) },
{ "i_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_ROLL].I) },
{ "d_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_ROLL].D) },
{ "p_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_YAW].P) },
{ "i_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_YAW].I) },
{ "d_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_YAW].D) },
{ "p_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDALT]) },
{ "i_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDALT]) },
{ "d_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDALT]) },
{ "p_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_ALT].P) },
{ "i_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_ALT].I) },
{ "d_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_ALT].D) },
{ "p_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDLEVEL]) },
{ "i_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDLEVEL]) },
{ "d_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDLEVEL]) },
{ "p_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_LEVEL].P) },
{ "i_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_LEVEL].I) },
{ "d_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_LEVEL].D) },
{ "p_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDVEL]) },
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDVEL]) },
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDVEL]) },
{ "p_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_VEL].P) },
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_VEL].I) },
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_VEL].D) },
{ "level_sensitivity", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 10, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, levelSensitivity) },
{ "level_limit", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 10, 120 }, PG_PID_PROFILE, offsetof(pidProfile_t, levelAngleLimit) },
@ -576,15 +576,15 @@ const clivalue_t valueTable[] = {
{ "horizon_tilt_effect", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 250 }, PG_PID_PROFILE, offsetof(pidProfile_t, horizon_tilt_effect) },
{ "horizon_tilt_expert_mode", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, horizon_tilt_expert_mode) },
#ifdef GPS
{ "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDPOS]) },
{ "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDPOS]) },
{ "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDPOS]) },
{ "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDPOSR]) },
{ "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDPOSR]) },
{ "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDPOSR]) },
{ "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDNAVR]) },
{ "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDNAVR]) },
{ "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDNAVR]) },
{ "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].P) },
{ "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].I) },
{ "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POS].D) },
{ "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POSR].P) },
{ "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POSR].I) },
{ "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_POSR].D) },
{ "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_NAVR].P) },
{ "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_NAVR].I) },
{ "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_NAVR].D) },
#endif
// PG_TELEMETRY_CONFIG

View File

@ -181,7 +181,7 @@ int32_t calculateAltHoldThrottleAdjustment(int32_t vel_tmp, float accZ_tmp, floa
if (!velocityControl) {
error = constrain(AltHold - estimatedAltitude, -500, 500);
error = applyDeadband(error, 10); // remove small P parameter to reduce noise near zero position
setVel = constrain((currentPidProfile->P8[PIDALT] * error / 128), -300, +300); // limit velocity to +/- 3 m/s
setVel = constrain((currentPidProfile->pid[PID_ALT].P * error / 128), -300, +300); // limit velocity to +/- 3 m/s
} else {
setVel = setVelocity;
}
@ -189,15 +189,15 @@ int32_t calculateAltHoldThrottleAdjustment(int32_t vel_tmp, float accZ_tmp, floa
// P
error = setVel - vel_tmp;
result = constrain((currentPidProfile->P8[PIDVEL] * error / 32), -300, +300);
result = constrain((currentPidProfile->pid[PID_VEL].P * error / 32), -300, +300);
// I
errorVelocityI += (currentPidProfile->I8[PIDVEL] * error);
errorVelocityI += (currentPidProfile->pid[PID_VEL].I * error);
errorVelocityI = constrain(errorVelocityI, -(8192 * 200), (8192 * 200));
result += errorVelocityI / 8192; // I in range +/-200
// D
result -= constrain(currentPidProfile->D8[PIDVEL] * (accZ_tmp + accZ_old) / 512, -150, 150);
result -= constrain(currentPidProfile->pid[PID_VEL].D * (accZ_tmp + accZ_old) / 512, -150, 150);
return result;
}

View File

@ -388,18 +388,18 @@ void GPS_reset_nav(void)
// Get the relevant P I D values and set the PID controllers
void gpsUsePIDs(pidProfile_t *pidProfile)
{
posholdPID_PARAM.kP = (float)pidProfile->P8[PIDPOS] / 100.0f;
posholdPID_PARAM.kI = (float)pidProfile->I8[PIDPOS] / 100.0f;
posholdPID_PARAM.kP = (float)pidProfile->pid[PID_POS].P / 100.0f;
posholdPID_PARAM.kI = (float)pidProfile->pid[PID_POS].I / 100.0f;
posholdPID_PARAM.Imax = POSHOLD_RATE_IMAX * 100;
poshold_ratePID_PARAM.kP = (float)pidProfile->P8[PIDPOSR] / 10.0f;
poshold_ratePID_PARAM.kI = (float)pidProfile->I8[PIDPOSR] / 100.0f;
poshold_ratePID_PARAM.kD = (float)pidProfile->D8[PIDPOSR] / 1000.0f;
poshold_ratePID_PARAM.kP = (float)pidProfile->pid[PID_POSR].P / 10.0f;
poshold_ratePID_PARAM.kI = (float)pidProfile->pid[PID_POSR].I / 100.0f;
poshold_ratePID_PARAM.kD = (float)pidProfile->pid[PID_POSR].D / 1000.0f;
poshold_ratePID_PARAM.Imax = POSHOLD_RATE_IMAX * 100;
navPID_PARAM.kP = (float)pidProfile->P8[PIDNAVR] / 10.0f;
navPID_PARAM.kI = (float)pidProfile->I8[PIDNAVR] / 100.0f;
navPID_PARAM.kD = (float)pidProfile->D8[PIDNAVR] / 1000.0f;
navPID_PARAM.kP = (float)pidProfile->pid[PID_NAVR].P / 10.0f;
navPID_PARAM.kI = (float)pidProfile->pid[PID_NAVR].I / 100.0f;
navPID_PARAM.kD = (float)pidProfile->pid[PID_NAVR].D / 1000.0f;
navPID_PARAM.Imax = POSHOLD_RATE_IMAX * 100;
}

View File

@ -74,34 +74,18 @@ PG_REGISTER_ARRAY_WITH_RESET_FN(pidProfile_t, MAX_PROFILE_COUNT, pidProfiles, PG
void resetPidProfile(pidProfile_t *pidProfile)
{
RESET_CONFIG(const pidProfile_t, pidProfile,
.P8[ROLL] = 44,
.I8[ROLL] = 40,
.D8[ROLL] = 30,
.P8[PITCH] = 58,
.I8[PITCH] = 50,
.D8[PITCH] = 35,
.P8[YAW] = 70,
.I8[YAW] = 45,
.D8[YAW] = 20,
.P8[PIDALT] = 50,
.I8[PIDALT] = 0,
.D8[PIDALT] = 0,
.P8[PIDPOS] = 15, // POSHOLD_P * 100,
.I8[PIDPOS] = 0, // POSHOLD_I * 100,
.D8[PIDPOS] = 0,
.P8[PIDPOSR] = 34, // POSHOLD_RATE_P * 10,
.I8[PIDPOSR] = 14, // POSHOLD_RATE_I * 100,
.D8[PIDPOSR] = 53, // POSHOLD_RATE_D * 1000,
.P8[PIDNAVR] = 25, // NAV_P * 10,
.I8[PIDNAVR] = 33, // NAV_I * 100,
.D8[PIDNAVR] = 83, // NAV_D * 1000,
.P8[PIDLEVEL] = 50,
.I8[PIDLEVEL] = 50,
.D8[PIDLEVEL] = 75,
.P8[PIDMAG] = 40,
.P8[PIDVEL] = 55,
.I8[PIDVEL] = 55,
.D8[PIDVEL] = 75,
.pid = {
[PID_ROLL] = { 40, 40, 30 },
[PID_PITCH] = { 58, 50, 35 },
[PID_YAW] = { 70, 45, 20 },
[PID_ALT] = { 50, 0, 0 },
[PID_POS] = { 15, 0, 0 }, // POSHOLD_P * 100, POSHOLD_I * 100,
[PID_POSR] = { 34, 14, 53 }, // POSHOLD_RATE_P * 10, POSHOLD_RATE_I * 100, POSHOLD_RATE_D * 1000,
[PID_NAVR] = { 25, 33, 83 }, // NAV_P * 10, NAV_I * 100, NAV_D * 1000
[PID_LEVEL] = { 50, 50, 75 },
[PID_MAG] = { 40, 0, 0 },
[PID_VEL] = { 55, 55, 75 }
},
.pidSumLimit = PIDSUM_LIMIT,
.pidSumLimitYaw = PIDSUM_LIMIT_YAW,
@ -249,15 +233,15 @@ static float crashGyroThreshold;
void pidInitConfig(const pidProfile_t *pidProfile) {
for(int axis = FD_ROLL; axis <= FD_YAW; axis++) {
Kp[axis] = PTERM_SCALE * pidProfile->P8[axis];
Ki[axis] = ITERM_SCALE * pidProfile->I8[axis];
Kd[axis] = DTERM_SCALE * pidProfile->D8[axis];
Kp[axis] = PTERM_SCALE * pidProfile->pid[axis].P;
Ki[axis] = ITERM_SCALE * pidProfile->pid[axis].I;
Kd[axis] = DTERM_SCALE * pidProfile->pid[axis].D;
}
dtermSetpointWeight = pidProfile->dtermSetpointWeight / 127.0f;
relaxFactor = 1.0f / (pidProfile->setpointRelaxRatio / 100.0f);
levelGain = pidProfile->P8[PIDLEVEL] / 10.0f;
horizonGain = pidProfile->I8[PIDLEVEL] / 10.0f;
horizonTransition = (float)pidProfile->D8[PIDLEVEL];
levelGain = pidProfile->pid[PID_LEVEL].P / 10.0f;
horizonGain = pidProfile->pid[PID_LEVEL].I / 10.0f;
horizonTransition = (float)pidProfile->pid[PID_LEVEL].D;
horizonTiltExpertMode = pidProfile->horizon_tilt_expert_mode;
horizonCutoffDegrees = (175 - pidProfile->horizon_tilt_effect) * 1.8f;
horizonFactorRatio = (100 - pidProfile->horizon_tilt_effect) * 0.01f;

View File

@ -35,16 +35,16 @@
#define DTERM_SCALE 0.000529f
typedef enum {
PIDROLL,
PIDPITCH,
PIDYAW,
PIDALT,
PIDPOS,
PIDPOSR,
PIDNAVR,
PIDLEVEL,
PIDMAG,
PIDVEL,
PID_ROLL,
PID_PITCH,
PID_YAW,
PID_ALT,
PID_POS,
PID_POSR,
PID_NAVR,
PID_LEVEL,
PID_MAG,
PID_VEL,
PID_ITEM_COUNT
} pidIndex_e;
@ -65,10 +65,14 @@ typedef enum {
PID_CRASH_RECOVERY_BEEP
} pidCrashRecovery_e;
typedef struct pid8_s {
uint8_t P;
uint8_t I;
uint8_t D;
} pid8_t;
typedef struct pidProfile_s {
uint8_t P8[PID_ITEM_COUNT];
uint8_t I8[PID_ITEM_COUNT];
uint8_t D8[PID_ITEM_COUNT];
pid8_t pid[PID_ITEM_COUNT];
uint8_t dterm_filter_type; // Filter selection for dterm
uint16_t dterm_lpf_hz; // Delta Filter in hz

View File

@ -325,9 +325,9 @@ void showProfilePage(void)
for (int axis = 0; axis < 3; ++axis) {
tfp_sprintf(lineBuffer, "%s P:%3d I:%3d D:%3d",
axisTitles[axis],
pidProfile->P8[axis],
pidProfile->I8[axis],
pidProfile->D8[axis]
pidProfile->pid[axis].P,
pidProfile->pid[axis].I,
pidProfile->pid[axis].D
);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);

View File

@ -408,21 +408,21 @@ static void osdDrawSingleElement(uint8_t item)
case OSD_ROLL_PIDS:
{
const pidProfile_t *pidProfile = currentPidProfile;
tfp_sprintf(buff, "ROL %3d %3d %3d", pidProfile->P8[PIDROLL], pidProfile->I8[PIDROLL], pidProfile->D8[PIDROLL]);
tfp_sprintf(buff, "ROL %3d %3d %3d", pidProfile->pid[PID_ROLL].P, pidProfile->pid[PID_ROLL].I, pidProfile->pid[PID_ROLL].D);
break;
}
case OSD_PITCH_PIDS:
{
const pidProfile_t *pidProfile = currentPidProfile;
tfp_sprintf(buff, "PIT %3d %3d %3d", pidProfile->P8[PIDPITCH], pidProfile->I8[PIDPITCH], pidProfile->D8[PIDPITCH]);
tfp_sprintf(buff, "PIT %3d %3d %3d", pidProfile->pid[PID_PITCH].P, pidProfile->pid[PID_PITCH].I, pidProfile->pid[PID_PITCH].D);
break;
}
case OSD_YAW_PIDS:
{
const pidProfile_t *pidProfile = currentPidProfile;
tfp_sprintf(buff, "YAW %3d %3d %3d", pidProfile->P8[PIDYAW], pidProfile->I8[PIDYAW], pidProfile->D8[PIDYAW]);
tfp_sprintf(buff, "YAW %3d %3d %3d", pidProfile->pid[PID_YAW].P, pidProfile->pid[PID_YAW].I, pidProfile->pid[PID_YAW].D);
break;
}

View File

@ -49,12 +49,12 @@ void targetConfiguration(void)
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
}
pidProfilesMutable(0)->P8[FD_ROLL] = 90;
pidProfilesMutable(0)->I8[FD_ROLL] = 44;
pidProfilesMutable(0)->D8[FD_ROLL] = 60;
pidProfilesMutable(0)->P8[FD_PITCH] = 90;
pidProfilesMutable(0)->I8[FD_PITCH] = 44;
pidProfilesMutable(0)->D8[FD_PITCH] = 60;
pidProfilesMutable(0)->pid[PID_ROLL].P = 90;
pidProfilesMutable(0)->pid[PID_ROLL].I = 44;
pidProfilesMutable(0)->pid[PID_ROLL].D = 60;
pidProfilesMutable(0)->pid[PID_PITCH].P = 90;
pidProfilesMutable(0)->pid[PID_PITCH].I = 44;
pidProfilesMutable(0)->pid[PID_PITCH].D = 60;
*customMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
*customMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R

View File

@ -86,12 +86,12 @@ void targetConfiguration(void)
pidConfigMutable()->pid_process_denom = 1;
}
pidProfilesMutable(0)->P8[FD_ROLL] = 90;
pidProfilesMutable(0)->I8[FD_ROLL] = 44;
pidProfilesMutable(0)->D8[FD_ROLL] = 60;
pidProfilesMutable(0)->P8[FD_PITCH] = 90;
pidProfilesMutable(0)->I8[FD_PITCH] = 44;
pidProfilesMutable(0)->D8[FD_PITCH] = 60;
pidProfilesMutable(0)->pid[PID_ROLL].P = 90;
pidProfilesMutable(0)->pid[PID_ROLL].I = 44;
pidProfilesMutable(0)->pid[PID_ROLL].D = 60;
pidProfilesMutable(0)->pid[PID_PITCH].P = 90;
pidProfilesMutable(0)->pid[PID_PITCH].I = 44;
pidProfilesMutable(0)->pid[PID_PITCH].D = 60;
*customMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
*customMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R

View File

@ -71,14 +71,14 @@ void targetConfiguration(void)
featureSet(FEATURE_TELEMETRY);
}
pidProfilesMutable(0)->P8[FD_ROLL] = 53;
pidProfilesMutable(0)->I8[FD_ROLL] = 45;
pidProfilesMutable(0)->D8[FD_ROLL] = 52;
pidProfilesMutable(0)->P8[FD_PITCH] = 53;
pidProfilesMutable(0)->I8[FD_PITCH] = 45;
pidProfilesMutable(0)->D8[FD_PITCH] = 52;
pidProfilesMutable(0)->P8[FD_YAW] = 64;
pidProfilesMutable(0)->D8[FD_YAW] = 18;
pidProfilesMutable(0)->pid[PID_ROLL].P = 53;
pidProfilesMutable(0)->pid[PID_ROLL].I = 45;
pidProfilesMutable(0)->pid[PID_ROLL].D = 52;
pidProfilesMutable(0)->pid[PID_PITCH].P = 53;
pidProfilesMutable(0)->pid[PID_PITCH].I = 45;
pidProfilesMutable(0)->pid[PID_PITCH].D = 52;
pidProfilesMutable(0)->pid[PID_YAW].P = 64;
pidProfilesMutable(0)->pid[PID_YAW].D = 18;
*customMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
*customMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R

View File

@ -70,14 +70,14 @@ void targetConfiguration(void)
featureSet(FEATURE_TELEMETRY);
}
pidProfilesMutable(0)->P8[FD_ROLL] = 53;
pidProfilesMutable(0)->I8[FD_ROLL] = 45;
pidProfilesMutable(0)->D8[FD_ROLL] = 52;
pidProfilesMutable(0)->P8[FD_PITCH] = 53;
pidProfilesMutable(0)->I8[FD_PITCH] = 45;
pidProfilesMutable(0)->D8[FD_PITCH] = 52;
pidProfilesMutable(0)->P8[FD_YAW] = 64;
pidProfilesMutable(0)->D8[FD_YAW] = 18;
pidProfilesMutable(0)->pid[FD_ROLL].P = 53;
pidProfilesMutable(0)->pid[FD_ROLL].I = 45;
pidProfilesMutable(0)->pid[FD_ROLL].D = 52;
pidProfilesMutable(0)->pid[FD_PITCH].P = 53;
pidProfilesMutable(0)->pid[FD_PITCH].I = 45;
pidProfilesMutable(0)->pid[FD_PITCH].D = 52;
pidProfilesMutable(0)->pid[FD_YAW].P = 64;
pidProfilesMutable(0)->pid[FD_YAW].D = 18;
*customMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
*customMotorMixerMutable(1) = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R

View File

@ -349,9 +349,9 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
break;
case BST_PID:
for (i = 0; i < PID_ITEM_COUNT; i++) {
bstWrite8(currentPidProfile->P8[i]);
bstWrite8(currentPidProfile->I8[i]);
bstWrite8(currentPidProfile->D8[i]);
bstWrite8(currentPidProfile->pid[i].P);
bstWrite8(currentPidProfile->pid[i].I);
bstWrite8(currentPidProfile->pid[i].D);
}
pidInitConfig(currentPidProfile);
break;
@ -465,9 +465,9 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
break;
case BST_SET_PID:
for (i = 0; i < PID_ITEM_COUNT; i++) {
currentPidProfile->P8[i] = bstRead8();
currentPidProfile->I8[i] = bstRead8();
currentPidProfile->D8[i] = bstRead8();
currentPidProfile->pid[i].P = bstRead8();
currentPidProfile->pid[i].I = bstRead8();
currentPidProfile->pid[i].D = bstRead8();
}
break;
case BST_SET_MODE_RANGE:

View File

@ -76,14 +76,14 @@ void targetConfiguration(void)
gyroConfigMutable()->gyro_sync_denom = 4;
pidConfigMutable()->pid_process_denom = 1;
pidProfilesMutable(0)->P8[ROLL] = 70;
pidProfilesMutable(0)->I8[ROLL] = 62;
pidProfilesMutable(0)->D8[ROLL] = 19;
pidProfilesMutable(0)->P8[PITCH] = 70;
pidProfilesMutable(0)->I8[PITCH] = 62;
pidProfilesMutable(0)->D8[PITCH] = 19;
pidProfilesMutable(0)->pid[PID_ROLL].P = 70;
pidProfilesMutable(0)->pid[PID_ROLL].I = 62;
pidProfilesMutable(0)->pid[PID_ROLL].D = 19;
pidProfilesMutable(0)->pid[PID_PITCH].P = 70;
pidProfilesMutable(0)->pid[PID_PITCH].I = 62;
pidProfilesMutable(0)->pid[PID_PITCH].D = 19;
controlRateProfilesMutable(0)->rcRate8 = 70;
pidProfilesMutable(0)->I8[PIDLEVEL] = 40;
pidProfilesMutable(0)->pid[PID_LEVEL].I = 40;
}
#endif

View File

@ -62,16 +62,16 @@ void targetConfiguration(void)
}*/
for (int profileId = 0; profileId < 2; profileId++) {
pidProfilesMutable(0)->P8[ROLL] = 60;
pidProfilesMutable(0)->I8[ROLL] = 70;
pidProfilesMutable(0)->D8[ROLL] = 17;
pidProfilesMutable(0)->P8[PITCH] = 80;
pidProfilesMutable(0)->I8[PITCH] = 90;
pidProfilesMutable(0)->D8[PITCH] = 18;
pidProfilesMutable(0)->P8[YAW] = 200;
pidProfilesMutable(0)->I8[YAW] = 45;
pidProfilesMutable(0)->P8[PIDLEVEL] = 30;
pidProfilesMutable(0)->D8[PIDLEVEL] = 30;
pidProfilesMutable(0)->pid[PID_ROLL].P = 60;
pidProfilesMutable(0)->pid[PID_ROLL].I = 70;
pidProfilesMutable(0)->pid[PID_ROLL].D = 17;
pidProfilesMutable(0)->pid[PID_PITCH].P = 80;
pidProfilesMutable(0)->pid[PID_PITCH].I = 90;
pidProfilesMutable(0)->pid[PID_PITCH].D = 18;
pidProfilesMutable(0)->pid[PID_YAW].P = 200;
pidProfilesMutable(0)->pid[PID_YAW].I = 45;
pidProfilesMutable(0)->pid[PID_LEVEL].P = 30;
pidProfilesMutable(0)->pid[PID_LEVEL].D = 30;
for (int rateProfileId = 0; rateProfileId < CONTROL_RATE_PROFILE_COUNT; rateProfileId++) {
controlRateProfilesMutable(rateProfileId)->rcRate8 = 100;

View File

@ -44,12 +44,12 @@ void targetConfiguration(void)
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
pidProfilesMutable(0)->P8[FD_ROLL] = 90;
pidProfilesMutable(0)->I8[FD_ROLL] = 44;
pidProfilesMutable(0)->D8[FD_ROLL] = 60;
pidProfilesMutable(0)->P8[FD_PITCH] = 90;
pidProfilesMutable(0)->I8[FD_PITCH] = 44;
pidProfilesMutable(0)->D8[FD_PITCH] = 60;
pidProfilesMutable(0)->pid[FD_ROLL].P = 90;
pidProfilesMutable(0)->pid[FD_ROLL].I = 44;
pidProfilesMutable(0)->pid[FD_ROLL].D = 60;
pidProfilesMutable(0)->pid[FD_PITCH].P = 90;
pidProfilesMutable(0)->pid[FD_PITCH].I = 44;
pidProfilesMutable(0)->pid[FD_PITCH].D = 60;
#endif
}
#endif

View File

@ -752,19 +752,19 @@ void handleSmartPortTelemetry(void)
} else if (telemetryConfig()->pidValuesAsTelemetry){
switch (t2Cnt) {
case 0:
tmp2 = currentPidProfile->P8[ROLL];
tmp2 += (currentPidProfile->P8[PITCH]<<8);
tmp2 += (currentPidProfile->P8[YAW]<<16);
tmp2 = currentPidProfile->pid[PID_ROLL].P;
tmp2 += (currentPidProfile->pid[PID_PITCH].P<<8);
tmp2 += (currentPidProfile->pid[PID_YAW].P<<16);
break;
case 1:
tmp2 = currentPidProfile->I8[ROLL];
tmp2 += (currentPidProfile->I8[PITCH]<<8);
tmp2 += (currentPidProfile->I8[YAW]<<16);
tmp2 = currentPidProfile->pid[PID_ROLL].I;
tmp2 += (currentPidProfile->pid[PID_PITCH].I<<8);
tmp2 += (currentPidProfile->pid[PID_YAW].I<<16);
break;
case 2:
tmp2 = currentPidProfile->D8[ROLL];
tmp2 += (currentPidProfile->D8[PITCH]<<8);
tmp2 += (currentPidProfile->D8[YAW]<<16);
tmp2 = currentPidProfile->pid[PID_ROLL].D;
tmp2 += (currentPidProfile->pid[PID_PITCH].D<<8);
tmp2 += (currentPidProfile->pid[PID_YAW].D<<16);
break;
case 3:
tmp2 = currentControlRateProfile->rates[FD_ROLL];