pid
This commit is contained in:
parent
f10dc1165d
commit
9ff363dc24
@ -23,15 +23,19 @@ public class TunerConstants {
|
||||
|
||||
// The steer motor uses any SwerveModule.SteerRequestType control request with the
|
||||
// output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput
|
||||
private static final Slot0Configs steerGains = new Slot0Configs()
|
||||
.withKP(52.109).withKI(0).withKD(3.0232)
|
||||
.withKS(0.24757).withKV(2.4715).withKA(0.062286)
|
||||
//private static final Slot0Configs steerGains = new Slot0Configs()
|
||||
// .withKP(68.294).withKI(0).withKD(4.7806)
|
||||
// .withKS(0.20754).withKV(2.4832).withKA(0.099824)
|
||||
// .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign);
|
||||
private static final Slot0Configs steerGains = new Slot0Configs()
|
||||
.withKP(43.502).withKI(0).withKD(2.7353)
|
||||
.withKS(0.027275).withKV(2.5818).withKA(0.1055)
|
||||
.withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign);
|
||||
// When using closed-loop control, the drive motor uses the control
|
||||
// output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput
|
||||
private static final Slot0Configs driveGains = new Slot0Configs()
|
||||
.withKP(0.1).withKI(0).withKD(0)
|
||||
.withKS(0).withKV(0.124);
|
||||
.withKP(63.167).withKI(0).withKD(0.54521)
|
||||
.withKS(0.18227).withKV(0.12483);
|
||||
|
||||
// The closed-loop output type to use for the steer motors;
|
||||
// This affects the PID/FF gains for the steer motors
|
||||
|
@ -124,9 +124,9 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
),
|
||||
new PPHolonomicDriveController(
|
||||
// PID constants for translation
|
||||
new PIDConstants(10, 0, 0),
|
||||
new PIDConstants(63.167, 0, 0.54521),
|
||||
// PID constants for rotation
|
||||
new PIDConstants(7, 0, 0)
|
||||
new PIDConstants(7.9735, 0, 0.038499)
|
||||
),
|
||||
config,
|
||||
// Assume the path needs to be flipped for Red vs Blue, this is normally the case
|
||||
@ -142,7 +142,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
}
|
||||
|
||||
/* The SysId routine to test */
|
||||
private SysIdRoutine m_sysIdRoutineToApply = m_sysIdRoutineTranslation;
|
||||
private SysIdRoutine m_sysIdRoutineToApply = m_sysIdRoutineSteer;
|
||||
|
||||
/**
|
||||
* Constructs a CTRE SwerveDrivetrain using the specified constants.
|
||||
|
Loading…
x
Reference in New Issue
Block a user