1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 16:25:31 +03:00

revise PID gains

This commit is contained in:
ctzsnooze 2024-10-10 10:16:11 +11:00
parent a853b6ced3
commit 33f92db305
2 changed files with 5 additions and 4 deletions

View file

@ -36,9 +36,9 @@
#define ALTITUDE_I_SCALE 0.003f
#define ALTITUDE_D_SCALE 0.01f
#define ALTITUDE_F_SCALE 0.01f
#define POSITION_P_SCALE 0.01f
#define POSITION_I_SCALE 0.01f
#define POSITION_D_SCALE 0.01f
#define POSITION_P_SCALE 0.5f
#define POSITION_I_SCALE 0.1f
#define POSITION_D_SCALE 0.1f
static pidCoefficient_t altitudePidCoeffs;
static float altitudeI = 0.0f;
@ -179,6 +179,7 @@ void positionControl(gpsLocation_t targetLocation, float deadband) {
// send setpoints to pid.c using a method similar to that in gpsRescueAngle[axis]
// value sent needs shoiuld be in degrees * 100
// values will have steps at GPS rate, if too jumpy we would need to upsample smooth them
posHoldAngle[AI_ROLL] = rollSetpoint;
posHoldAngle[AI_PITCH] = pitchSetpoint;

View file

@ -39,7 +39,7 @@ PG_RESET_TEMPLATE(autopilotConfig_t, autopilotConfig,
.altitude_D = 15,
.altitude_F = 15,
.position_P = 15,
.position_I = 40,
.position_I = 15,
.position_D = 15,
// .position_F = 0,
.position_filter_hz = 75,