Skip to content

Commit f27088f

Browse files
committed
Remade swerve configs into an abstract class
1 parent 91fabeb commit f27088f

File tree

6 files changed

+155
-9
lines changed

6 files changed

+155
-9
lines changed

gradlew

100644100755
File mode changed.

src/main/java/org/frc6423/frc2025/Constants.java

Lines changed: 71 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,11 @@
1414
import org.frc6423.frc2025.util.swerveUtil.ModuleConfig;
1515
import org.frc6423.frc2025.util.swerveUtil.ModuleConfig.moduleType;
1616

17+
import com.ctre.phoenix6.configs.CANcoderConfiguration;
18+
import com.ctre.phoenix6.configs.FeedbackConfigs;
1719
import com.ctre.phoenix6.configs.TalonFXConfiguration;
20+
import com.ctre.phoenix6.signals.FeedbackSensorSourceValue;
21+
import com.ctre.phoenix6.signals.NeutralModeValue;
1822

1923
import 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
}

src/main/java/org/frc6423/frc2025/subsystems/swerve/module/ModuleIOSim.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,8 +35,9 @@ public ModuleIOSim(ModuleConfig config) {
3535
DCMotor pivotMotor = DCMotor.getKrakenX60(1);
3636
DCMotor driveMotor = DCMotor.getKrakenX60(1);
3737

38-
// ! Apply talon config
3938
m_driveMotor = new TalonFX(config.kDriveID);
39+
m_driveMotor.getConfigurator().apply(config.kDriveConfig);
40+
4041
m_driveVoltage = new VoltageOut(0.0).withEnableFOC(true);
4142
m_driveVelocityControl = new VelocityTorqueCurrentFOC(0.0).withSlot(0);
4243

src/main/java/org/frc6423/frc2025/util/swerveUtil/ModuleConfig.java

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,11 @@
66

77
package org.frc6423.frc2025.util.swerveUtil;
88

9+
import com.ctre.phoenix6.configs.CANcoderConfiguration;
910
import com.ctre.phoenix6.configs.TalonFXConfiguration;
11+
import com.ctre.phoenix6.hardware.CANcoder;
12+
import com.ctre.phoenix6.signals.FeedbackSensorSourceValue;
13+
import com.ctre.phoenix6.signals.InvertedValue;
1014

1115
import edu.wpi.first.math.geometry.Rotation2d;
1216

@@ -22,6 +26,7 @@ public class ModuleConfig {
2226
public boolean kPivotInverted;
2327

2428
public TalonFXConfiguration kPivotConfig, kDriveConfig;
29+
public CANcoderConfiguration kCANcoderConfig;
2530

2631
public static enum moduleType {
2732
SPARKMAX,
@@ -37,7 +42,8 @@ public ModuleConfig(
3742
Rotation2d pivotOffset,
3843
boolean pivotInverted,
3944
TalonFXConfiguration pivotConfig,
40-
TalonFXConfiguration driveConfig) {
45+
TalonFXConfiguration driveConfig,
46+
CANcoderConfiguration CANcoderConfig) {
4147
this.kIndex = index;
4248
this.kModuletype = type;
4349
this.kPivotID = pivotID;
@@ -46,8 +52,16 @@ public ModuleConfig(
4652
this.kPivotOffset = pivotOffset;
4753
this.kPivotInverted = pivotInverted;
4854

55+
pivotConfig.MotorOutput.Inverted = pivotInverted
56+
? InvertedValue.Clockwise_Positive
57+
: InvertedValue.CounterClockwise_Positive;
58+
59+
pivotConfig.Feedback.FeedbackRemoteSensorID = kPivotABSID;
60+
4961
this.kPivotConfig = pivotConfig;
5062
this.kDriveConfig = driveConfig;
63+
this.kCANcoderConfig = CANcoderConfig;
64+
5165
}
5266

5367
public ModuleConfig(
Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
1+
package org.frc6423.frc2025.util.swerveUtil;
2+
3+
import com.ctre.phoenix6.configs.CANcoderConfiguration;
4+
import com.ctre.phoenix6.configs.TalonFXConfiguration;
5+
6+
import edu.wpi.first.math.controller.PIDController;
7+
import edu.wpi.first.math.geometry.Translation2d;
8+
9+
public abstract class SwerveConfig {
10+
11+
public abstract double getMaxLinearSpeedMetersPerSec();
12+
13+
public abstract double getMaxLinearAccelMetersPerSecSqrd();
14+
15+
public double getMaxAngularSpeedRadsPerSec() {
16+
double drivebaseRadius = Math.hypot(getTrackWidthX() / 2.0, getTrackWidthY() / 2.0);
17+
return getMaxLinearSpeedMetersPerSec() / drivebaseRadius;
18+
}
19+
20+
public double getMaxAngularSpeedRadsPerSecSqrd() {
21+
double drivebaseRadius = Math.hypot(getTrackWidthX() / 2.0, getTrackWidthY() / 2.0);
22+
return getMaxLinearAccelMetersPerSecSqrd()/drivebaseRadius;
23+
}
24+
25+
public abstract double getRobotMass();
26+
27+
public abstract double getRobotWidth();
28+
29+
public abstract double getRobotLength();
30+
31+
public abstract double getTrackWidthY();
32+
33+
public abstract double getTrackWidthX();
34+
35+
public abstract double getBumperWidth();
36+
37+
public abstract double getBumperLength();
38+
39+
public abstract double getWheelRadius();
40+
41+
public abstract double getPivotReduction();
42+
43+
public abstract double getDriveReduction();
44+
45+
public double getPivotCurrentLimit() {
46+
return 40.0;
47+
}
48+
49+
public double getDriveCurrentLimit() {
50+
return 40.0;
51+
}
52+
53+
public abstract PIDController getRotationalFeedback();
54+
55+
public abstract PIDController getTranslationFeedback();
56+
57+
public abstract Translation2d[] getModuleLocs();
58+
59+
public abstract ModuleConfig[] getModuleConfigs();
60+
61+
public abstract CANcoderConfiguration getCANcoderConfig();
62+
63+
public abstract TalonFXConfiguration getPivotConfig();
64+
65+
public abstract TalonFXConfiguration getDriveConfig();
66+
}

src/main/java/org/frc6423/frc2025/util/swerveUtil/SwerveConfig.java renamed to src/main/java/org/frc6423/frc2025/util/swerveUtil/SwerveConfig.legacy

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
// Open Source Software; you can modify and/or share it under the terms of
55
// MIT license file in the root directory of this project
66

7-
package org.frc6423.frc2025.util.swerveUtil;
7+
// package org.frc6423.frc2025.util.swerveUtil;
88

99
import edu.wpi.first.math.geometry.Translation2d;
1010

0 commit comments

Comments
 (0)