mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-26 01:35:35 +03:00
PID: LuxFloat rewritten from scratch. New I-term back-tracking for anti-windup prevention
AIRMODE: Air mode anti-windup improvements PID: Remove integer PID (leave only one PID controller), remove pid_controller setting, remove float-point PID parameters (scale integer parameters to use in float-point PIDC) PID: New set of PID tuning multipliers for better tuning range PID: Make max_angle_inclination a PID-profile variable PID: Reinstate yaw_p_limit PID: Switch to a noise-robust differentiator Remove GTUNE PID: Use same self-leveling strength for ANGLE and HORIZON PID: Self-leveling LPF to smooth out leveling response to rapid attitude or target angle change
This commit is contained in:
parent
6269f55a0e
commit
f1aa9e6f44
34 changed files with 250 additions and 826 deletions
|
@ -358,7 +358,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
|
|||
{ BOXGOV, "GOVERNOR;", 18 },
|
||||
{ BOXOSD, "OSD SW;", 19 },
|
||||
{ BOXTELEMETRY, "TELEMETRY;", 20 },
|
||||
{ BOXGTUNE, "GTUNE;", 21 },
|
||||
//{ BOXGTUNE, "GTUNE;", 21 },
|
||||
{ BOXSERVO1, "SERVO1;", 23 },
|
||||
{ BOXSERVO2, "SERVO2;", 24 },
|
||||
{ BOXSERVO3, "SERVO3;", 25 },
|
||||
|
@ -715,10 +715,6 @@ void mspInit(serialConfig_t *serialConfig)
|
|||
activeBoxIds[activeBoxIdCount++] = BOXFAILSAFE;
|
||||
}
|
||||
|
||||
#ifdef GTUNE
|
||||
activeBoxIds[activeBoxIdCount++] = BOXGTUNE;
|
||||
#endif
|
||||
|
||||
memset(mspPorts, 0x00, sizeof(mspPorts));
|
||||
mspAllocateSerialPorts(serialConfig);
|
||||
}
|
||||
|
@ -748,7 +744,6 @@ static uint32_t packFlightModeFlags(void)
|
|||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGOV)) << BOXGOV |
|
||||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXOSD)) << BOXOSD |
|
||||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXTELEMETRY)) << BOXTELEMETRY |
|
||||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGTUNE)) << BOXGTUNE |
|
||||
IS_ENABLED(ARMING_FLAG(ARMED)) << BOXARM |
|
||||
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX |
|
||||
IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE |
|
||||
|
@ -994,29 +989,10 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
break;
|
||||
case MSP_PID:
|
||||
headSerialReply(3 * PID_ITEM_COUNT);
|
||||
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) { // convert float stuff into uint8_t to keep backwards compatability with all 8-bit shit with new pid
|
||||
for (i = 0; i < 3; i++) {
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.P_f[i] * 10.0f), 0, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.I_f[i] * 100.0f), 0, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.D_f[i] * 1000.0f), 0, 255));
|
||||
}
|
||||
for (i = 3; i < PID_ITEM_COUNT; i++) {
|
||||
if (i == PIDLEVEL) {
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.A_level * 10.0f), 0, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.H_level * 10.0f), 0, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.H_sensitivity), 0, 255));
|
||||
} else {
|
||||
serialize8(currentProfile->pidProfile.P8[i]);
|
||||
serialize8(currentProfile->pidProfile.I8[i]);
|
||||
serialize8(currentProfile->pidProfile.D8[i]);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
serialize8(currentProfile->pidProfile.P8[i]);
|
||||
serialize8(currentProfile->pidProfile.I8[i]);
|
||||
serialize8(currentProfile->pidProfile.D8[i]);
|
||||
}
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
serialize8(currentProfile->pidProfile.P8[i]);
|
||||
serialize8(currentProfile->pidProfile.I8[i]);
|
||||
serialize8(currentProfile->pidProfile.D8[i]);
|
||||
}
|
||||
break;
|
||||
case MSP_PIDNAMES:
|
||||
|
@ -1025,7 +1001,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
break;
|
||||
case MSP_PID_CONTROLLER:
|
||||
headSerialReply(1);
|
||||
serialize8(currentProfile->pidProfile.pidController);
|
||||
serialize8(2); // FIXME: Report as LuxFloat
|
||||
break;
|
||||
case MSP_MODE_RANGES:
|
||||
headSerialReply(4 * MAX_MODE_ACTIVATION_CONDITION_COUNT);
|
||||
|
@ -1430,33 +1406,13 @@ static bool processInCommand(void)
|
|||
masterConfig.looptime = read16();
|
||||
break;
|
||||
case MSP_SET_PID_CONTROLLER:
|
||||
currentProfile->pidProfile.pidController = constrain(read8(), 1, 2); // Temporary configurator compatibility
|
||||
pidSetController(currentProfile->pidProfile.pidController);
|
||||
// FIXME: Do nothing
|
||||
break;
|
||||
case MSP_SET_PID:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) {
|
||||
for (i = 0; i < 3; i++) {
|
||||
currentProfile->pidProfile.P_f[i] = (float)read8() / 10.0f;
|
||||
currentProfile->pidProfile.I_f[i] = (float)read8() / 100.0f;
|
||||
currentProfile->pidProfile.D_f[i] = (float)read8() / 1000.0f;
|
||||
}
|
||||
for (i = 3; i < PID_ITEM_COUNT; i++) {
|
||||
if (i == PIDLEVEL) {
|
||||
currentProfile->pidProfile.A_level = (float)read8() / 10.0f;
|
||||
currentProfile->pidProfile.H_level = (float)read8() / 10.0f;
|
||||
currentProfile->pidProfile.H_sensitivity = read8();
|
||||
} else {
|
||||
currentProfile->pidProfile.P8[i] = read8();
|
||||
currentProfile->pidProfile.I8[i] = read8();
|
||||
currentProfile->pidProfile.D8[i] = read8();
|
||||
}
|
||||
}
|
||||
} else {
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
currentProfile->pidProfile.P8[i] = read8();
|
||||
currentProfile->pidProfile.I8[i] = read8();
|
||||
currentProfile->pidProfile.D8[i] = read8();
|
||||
}
|
||||
for (i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
currentProfile->pidProfile.P8[i] = read8();
|
||||
currentProfile->pidProfile.I8[i] = read8();
|
||||
currentProfile->pidProfile.D8[i] = read8();
|
||||
}
|
||||
break;
|
||||
case MSP_SET_MODE_RANGE:
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue