77
88package frc .robot .subsystems .swerve ;
99
10+ import com .ctre .phoenix6 .configs .CANcoderConfiguration ;
11+ import com .ctre .phoenix6 .configs .CurrentLimitsConfigs ;
12+ import com .ctre .phoenix6 .configs .Pigeon2Configuration ;
1013import com .ctre .phoenix6 .configs .Slot0Configs ;
14+ import com .ctre .phoenix6 .configs .TalonFXConfiguration ;
1115import com .ctre .phoenix6 .mechanisms .swerve .SwerveDrivetrainConstants ;
1216import com .ctre .phoenix6 .mechanisms .swerve .SwerveModule .ClosedLoopOutputType ;
1317import com .ctre .phoenix6 .mechanisms .swerve .SwerveModuleConstants ;
@@ -28,7 +32,7 @@ public class TunerConstants {
2832 // When using closed-loop control, the drive motor uses the control
2933 // output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput
3034 private static final Slot0Configs driveGains =
31- new Slot0Configs ().withKP (.1 ).withKI (0 ).withKD (0 ).withKS (0 ).withKV (0.12 ).withKA (0 );
35+ new Slot0Configs ().withKP (3 ).withKI (0 ).withKD (0 ).withKS (0 ).withKV (0 ).withKA (0 );
3236
3337 // The closed-loop output type to use for the steer motors;
3438 // This affects the PID/FF gains for the steer motors
@@ -39,7 +43,24 @@ public class TunerConstants {
3943
4044 // The stator current at which the wheels start to slip;
4145 // This needs to be tuned to your individual robot
42- private static final double kSlipCurrentA = 75.0 ;
46+ private static final double kSlipCurrentA = 150.0 ;
47+
48+ // Initial configs for the drive and steer motors and the CANcoder; these cannot be null.
49+ // Some configs will be overwritten; check the `with*InitialConfigs()` API documentation.
50+ private static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration ();
51+ private static final TalonFXConfiguration steerInitialConfigs =
52+ new TalonFXConfiguration ()
53+ .withCurrentLimits (
54+ new CurrentLimitsConfigs ()
55+ // Swerve azimuth does not require much torque output, so we can set a relatively
56+ // low
57+ // stator current limit to help avoid brownouts without impacting performance.
58+ .withStatorCurrentLimit (60 )
59+ .withStatorCurrentLimitEnable (true ));
60+ private static final CANcoderConfiguration cancoderInitialConfigs = new CANcoderConfiguration ();
61+ // Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs
62+ private static final Pigeon2Configuration pigeonConfigs = null ;
63+
4364 // Theoretical free speed (m/s) at 12v applied output;
4465 // This needs to be tuned to your individual robot
4566 public static final double kSpeedAt12VoltsMps = 5.96 ;
@@ -52,12 +73,11 @@ public class TunerConstants {
5273 private static final double kSteerGearRatio = 21.428571428571427 ;
5374 private static final double kWheelRadiusInches = 2 ;
5475
55- private static final boolean kSteerMotorReversed = true ;
5676 private static final boolean kInvertLeftSide = false ;
5777 private static final boolean kInvertRightSide = true ;
5878
5979 private static final String kCANbusName = "mani" ;
60- private static final int kPigeonId = 24 ;
80+ private static final int kPigeonId = 4 ;
6181
6282 // These are only used for simulation
6383 private static final double kSteerInertia = 0.00001 ;
@@ -67,7 +87,10 @@ public class TunerConstants {
6787 private static final double kDriveFrictionVoltage = 0.25 ;
6888
6989 private static final SwerveDrivetrainConstants DrivetrainConstants =
70- new SwerveDrivetrainConstants ().withPigeon2Id (kPigeonId ).withCANbusName (kCANbusName );
90+ new SwerveDrivetrainConstants ()
91+ .withCANbusName (kCANbusName )
92+ .withPigeon2Id (kPigeonId )
93+ .withPigeon2Configs (pigeonConfigs );
7194
7295 private static final SwerveModuleConstantsFactory ConstantCreator =
7396 new SwerveModuleConstantsFactory ()
@@ -86,80 +109,90 @@ public class TunerConstants {
86109 .withDriveFrictionVoltage (kDriveFrictionVoltage )
87110 .withFeedbackSource (SteerFeedbackType .FusedCANcoder )
88111 .withCouplingGearRatio (kCoupleRatio )
89- .withSteerMotorInverted (kSteerMotorReversed );
112+ .withDriveMotorInitialConfigs (driveInitialConfigs )
113+ .withSteerMotorInitialConfigs (steerInitialConfigs )
114+ .withCANcoderInitialConfigs (cancoderInitialConfigs );
90115
91116 // Front Left
92- private static final int kFrontLeftDriveMotorId = 1 ;
93- private static final int kFrontLeftSteerMotorId = 8 ;
94- private static final int kFrontLeftEncoderId = 2 ;
95- private static final double kFrontLeftEncoderOffset = -0.067626953125 ;
117+ private static final int kFrontLeftDriveMotorId = 8 ;
118+ private static final int kFrontLeftSteerMotorId = 7 ;
119+ private static final int kFrontLeftEncoderId = 23 ;
120+ private static final double kFrontLeftEncoderOffset = -0.399658203125 ;
121+ private static final boolean kFrontLeftSteerInvert = true ;
96122
97- private static final double kFrontLeftXPosInches = 10.375 ;
98- private static final double kFrontLeftYPosInches = 10.375 ;
123+ private static final double kFrontLeftXPosInches = 11 ;
124+ private static final double kFrontLeftYPosInches = 11 ;
99125
100126 // Front Right
101- private static final int kFrontRightDriveMotorId = 6 ;
102- private static final int kFrontRightSteerMotorId = 7 ;
103- private static final int kFrontRightEncoderId = 9 ;
104- private static final double kFrontRightEncoderOffset = -0.27099609375 ;
127+ private static final int kFrontRightDriveMotorId = 9 ;
128+ private static final int kFrontRightSteerMotorId = 21 ;
129+ private static final int kFrontRightEncoderId = 22 ;
130+ private static final double kFrontRightEncoderOffset = -0.46142578125 ;
131+ private static final boolean kFrontRightSteerInvert = true ;
105132
106- private static final double kFrontRightXPosInches = 10.375 ;
107- private static final double kFrontRightYPosInches = -10.375 ;
133+ private static final double kFrontRightXPosInches = 11 ;
134+ private static final double kFrontRightYPosInches = -11 ;
108135
109136 // Back Left
110137 private static final int kBackLeftDriveMotorId = 2 ;
111- private static final int kBackLeftSteerMotorId = 4 ;
112- private static final int kBackLeftEncoderId = 1 ;
113- private static final double kBackLeftEncoderOffset = -0.125732421875 ;
138+ private static final int kBackLeftSteerMotorId = 0 ;
139+ private static final int kBackLeftEncoderId = 24 ;
140+ private static final double kBackLeftEncoderOffset = 0.275390625 ;
141+ private static final boolean kBackLeftSteerInvert = true ;
114142
115- private static final double kBackLeftXPosInches = -10.375 ;
116- private static final double kBackLeftYPosInches = 10.375 ;
143+ private static final double kBackLeftXPosInches = -11 ;
144+ private static final double kBackLeftYPosInches = 11 ;
117145
118146 // Back Right
119- private static final int kBackRightDriveMotorId = 5 ;
120- private static final int kBackRightSteerMotorId = 0 ;
121- private static final int kBackRightEncoderId = 0 ;
122- private static final double kBackRightEncoderOffset = 0.41455078125 ;
147+ private static final int kBackRightDriveMotorId = 1 ;
148+ private static final int kBackRightSteerMotorId = 3 ;
149+ private static final int kBackRightEncoderId = 25 ;
150+ private static final double kBackRightEncoderOffset = -0.2666015625 ;
151+ private static final boolean kBackRightSteerInvert = true ;
123152
124- private static final double kBackRightXPosInches = -10.375 ;
125- private static final double kBackRightYPosInches = -10.375 ;
153+ private static final double kBackRightXPosInches = -11 ;
154+ private static final double kBackRightYPosInches = -11 ;
126155
127156 private static final SwerveModuleConstants FrontLeft =
128157 ConstantCreator .createModuleConstants (
129- kFrontLeftSteerMotorId ,
130- kFrontLeftDriveMotorId ,
131- kFrontLeftEncoderId ,
132- kFrontLeftEncoderOffset ,
133- Units .inchesToMeters (kFrontLeftXPosInches ),
134- Units .inchesToMeters (kFrontLeftYPosInches ),
135- kInvertLeftSide );
158+ kFrontLeftSteerMotorId ,
159+ kFrontLeftDriveMotorId ,
160+ kFrontLeftEncoderId ,
161+ kFrontLeftEncoderOffset ,
162+ Units .inchesToMeters (kFrontLeftXPosInches ),
163+ Units .inchesToMeters (kFrontLeftYPosInches ),
164+ kInvertLeftSide )
165+ .withSteerMotorInverted (kFrontLeftSteerInvert );
136166 private static final SwerveModuleConstants FrontRight =
137167 ConstantCreator .createModuleConstants (
138- kFrontRightSteerMotorId ,
139- kFrontRightDriveMotorId ,
140- kFrontRightEncoderId ,
141- kFrontRightEncoderOffset ,
142- Units .inchesToMeters (kFrontRightXPosInches ),
143- Units .inchesToMeters (kFrontRightYPosInches ),
144- kInvertRightSide );
168+ kFrontRightSteerMotorId ,
169+ kFrontRightDriveMotorId ,
170+ kFrontRightEncoderId ,
171+ kFrontRightEncoderOffset ,
172+ Units .inchesToMeters (kFrontRightXPosInches ),
173+ Units .inchesToMeters (kFrontRightYPosInches ),
174+ kInvertRightSide )
175+ .withSteerMotorInverted (kFrontRightSteerInvert );
145176 private static final SwerveModuleConstants BackLeft =
146177 ConstantCreator .createModuleConstants (
147- kBackLeftSteerMotorId ,
148- kBackLeftDriveMotorId ,
149- kBackLeftEncoderId ,
150- kBackLeftEncoderOffset ,
151- Units .inchesToMeters (kBackLeftXPosInches ),
152- Units .inchesToMeters (kBackLeftYPosInches ),
153- kInvertLeftSide );
178+ kBackLeftSteerMotorId ,
179+ kBackLeftDriveMotorId ,
180+ kBackLeftEncoderId ,
181+ kBackLeftEncoderOffset ,
182+ Units .inchesToMeters (kBackLeftXPosInches ),
183+ Units .inchesToMeters (kBackLeftYPosInches ),
184+ kInvertLeftSide )
185+ .withSteerMotorInverted (kBackLeftSteerInvert );
154186 private static final SwerveModuleConstants BackRight =
155187 ConstantCreator .createModuleConstants (
156- kBackRightSteerMotorId ,
157- kBackRightDriveMotorId ,
158- kBackRightEncoderId ,
159- kBackRightEncoderOffset ,
160- Units .inchesToMeters (kBackRightXPosInches ),
161- Units .inchesToMeters (kBackRightYPosInches ),
162- kInvertRightSide );
188+ kBackRightSteerMotorId ,
189+ kBackRightDriveMotorId ,
190+ kBackRightEncoderId ,
191+ kBackRightEncoderOffset ,
192+ Units .inchesToMeters (kBackRightXPosInches ),
193+ Units .inchesToMeters (kBackRightYPosInches ),
194+ kInvertRightSide )
195+ .withSteerMotorInverted (kBackRightSteerInvert );
163196
164197 public static final CommandSwerveDrivetrain DriveTrain =
165198 new CommandSwerveDrivetrain (
0 commit comments