1414import org .frc6423 .frc2025 .util .swerveUtil .ModuleConfig ;
1515import org .frc6423 .frc2025 .util .swerveUtil .ModuleConfig .moduleType ;
1616
17+ import com .ctre .phoenix6 .configs .CANcoderConfiguration ;
18+ import com .ctre .phoenix6 .configs .FeedbackConfigs ;
1719import com .ctre .phoenix6 .configs .TalonFXConfiguration ;
20+ import com .ctre .phoenix6 .signals .FeedbackSensorSourceValue ;
21+ import com .ctre .phoenix6 .signals .NeutralModeValue ;
1822
1923import org .frc6423 .frc2025 .util .swerveUtil .SwerveConfig ;
2024
@@ -66,12 +70,31 @@ public static DeployMode getDeployMode() {
6670 }
6771
6872 // * SUBSYSTEM CONSTANTS
69- public class KDriveConstants {
70-
71- private static final TalonFXConfiguration kPivotMotorConfig = new TalonFXConfiguration ()
72- .
73-
73+ public class KDriveConstants {
7474 // Swerve Configs
75+ public static final SwerveConfig kCompBotConfig =
76+ new SwerveConfig (
77+ new ModuleConfig [] {
78+ new ModuleConfig (1 , moduleType .TALONFX , 1 , 2 , 0 , Rotation2d .fromRadians (0 ), true , getPivotConfig (), getDriveConfig (), getCANcoderConfig ()),
79+ new ModuleConfig (2 , moduleType .TALONFX , 3 , 4 , 1 , Rotation2d .fromRadians (0 ), true , getPivotConfig (), getDriveConfig (), getCANcoderConfig ()),
80+ new ModuleConfig (3 , moduleType .TALONFX , 5 , 6 , 2 , Rotation2d .fromRadians (0 ), true , getPivotConfig (), getDriveConfig (), getCANcoderConfig ()),
81+ new ModuleConfig (4 , moduleType .TALONFX , 7 , 8 , 3 , Rotation2d .fromRadians (0 ), true , getPivotConfig (), getDriveConfig (), getCANcoderConfig ())
82+ },
83+ new Translation2d [] {
84+ new Translation2d (0.381 , 0.381 ),
85+ new Translation2d (0.381 , -0.381 ),
86+ new Translation2d (-0.381 , 0.381 ),
87+ new Translation2d (-0.381 , -0.381 )
88+ },
89+ 23.47 ,
90+ 23.47 ,
91+ 2 ,
92+ 2 ,
93+ 56 , // !
94+ Units .feetToMeters (16 ),
95+ Units .feetToMeters (16 ),
96+ 100 );
97+
7598 public static final SwerveConfig kDevBotConfig =
7699 new SwerveConfig (
77100 new ModuleConfig [] {
@@ -118,7 +141,8 @@ public static enum DriveControlMode {
118141 public static final double kDriveReduction = 5 / 1 ;
119142
120143 public static final double kVoltageCompensation = 12.0 ;
121- public static final int kSmartCurrentLimit = 40 ;
144+ public static final int kPivotCurrentLimitAmps = 40 ;
145+ public static final int kDriveCurrentLimitAmps = 40 ;
122146
123147 public static final double kWheelRadius = Units .inchesToMeters (4 );
124148
@@ -129,5 +153,46 @@ public static enum DriveControlMode {
129153 public static final double kDriveP = 1 ;
130154 public static final double kDriveI = 0 ;
131155 public static final double kDriveD = 0 ;
156+
157+ private static TalonFXConfiguration getPivotConfig () {
158+ TalonFXConfiguration config = new TalonFXConfiguration ();
159+
160+ config .Audio .BeepOnBoot = true ; // boop
161+
162+ config .MotorOutput .NeutralMode = NeutralModeValue .Brake ;
163+
164+ config .CurrentLimits .StatorCurrentLimit = kPivotCurrentLimitAmps ;
165+ config .CurrentLimits .StatorCurrentLimitEnable = true ;
166+
167+ // Torque
168+ config .TorqueCurrent .PeakForwardTorqueCurrent = kPivotCurrentLimitAmps ;
169+ config .TorqueCurrent .PeakReverseTorqueCurrent = -kPivotCurrentLimitAmps ;
170+
171+ // Feedback config
172+ config .Feedback .FeedbackSensorSource = FeedbackSensorSourceValue .FusedCANcoder ;
173+ config .Feedback .RotorToSensorRatio = kPivotReduction ;
174+ config .Feedback .SensorToMechanismRatio = 1.0 ;
175+ config .Feedback .FeedbackRotorOffset = 0.0 ;
176+ config .ClosedLoopGeneral .ContinuousWrap = true ; // Takes the shortest path
177+
178+ // Gains
179+ config .Slot0 .kP = 0.0 ;
180+ config .Slot0 .kI = 0.0 ;
181+ config .Slot0 .kD = 0.0 ;
182+
183+ config .Slot0 .kV = 0.0 ;
184+ config .Slot0 .kA = 0.0 ;
185+ config .Slot0 .kS = 0.0 ;
186+
187+ config .MotionMagic .MotionMagicCruiseVelocity = 0 ;
188+ config .MotionMagic .MotionMagicAcceleration = 0 ;
189+ config .MotionMagic .MotionMagicJerk = 0 ;
190+
191+ return config ;
192+ }
193+
194+ private static TalonFXConfiguration getDriveConfig () {}
195+
196+ private static CANcoderConfiguration getCANcoderConfig () {}
132197 }
133198}
0 commit comments