Skip to content
This repository was archived by the owner on May 19, 2024. It is now read-only.

Commit 66d88f5

Browse files
committed
refactor(swerve): Move swerve constants out of library.
1 parent b8dd291 commit 66d88f5

File tree

4 files changed

+47
-66
lines changed

4 files changed

+47
-66
lines changed

Diff for: src/main/java/frc/lib/controller/SwerveModuleIOCustom.java

+9-9
Original file line numberDiff line numberDiff line change
@@ -4,11 +4,8 @@
44
import edu.wpi.first.math.kinematics.SwerveModulePosition;
55
import edu.wpi.first.math.kinematics.SwerveModuleState;
66
import edu.wpi.first.math.util.Units;
7-
import frc.lib.CAN;
8-
import frc.lib.config.MechanismConfig;
97
import frc.lib.controller.PositionControllerIO.PositionControllerIOValues;
108
import frc.lib.controller.VelocityControllerIO.VelocityControllerIOValues;
11-
import frc.robot.swerve.SwerveFactory;
129

1310
/** Custom swerve module. */
1411
public class SwerveModuleIOCustom implements SwerveModuleIO {
@@ -25,18 +22,21 @@ public class SwerveModuleIOCustom implements SwerveModuleIO {
2522
/** Drive motor values. */
2623
private final VelocityControllerIOValues driveMotorValues = new VelocityControllerIOValues();
2724

28-
private final double wheelCircumference = Units.inchesToMeters(4.0) * Math.PI;
25+
/** Wheel circumference. */
26+
private final double wheelCircumference;
2927

3028
/** Module setpoint */
3129
private SwerveModuleState setpoint;
3230

3331
public SwerveModuleIOCustom(
34-
CAN steer, CAN azimuth, CAN drive, MechanismConfig steerConfig, MechanismConfig driveConfig) {
35-
steerMotor = SwerveFactory.createSteerMotor(steer, azimuth, steerConfig);
36-
steerMotor.configure();
32+
PositionControllerIO steerMotor, VelocityControllerIO driveMotor, double wheelCircumference) {
33+
this.steerMotor = steerMotor;
34+
this.steerMotor.configure();
3735

38-
driveMotor = SwerveFactory.createDriveMotor(drive, driveConfig);
39-
driveMotor.configure();
36+
this.driveMotor = driveMotor;
37+
this.driveMotor.configure();
38+
39+
this.wheelCircumference = wheelCircumference;
4040

4141
setpoint = new SwerveModuleState();
4242
}

Diff for: src/main/java/frc/robot/auto/Auto.java

+1-2
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,6 @@
1414
import frc.robot.odometry.Odometry;
1515
import frc.robot.superstructure.Superstructure;
1616
import frc.robot.swerve.Swerve;
17-
import frc.robot.swerve.SwerveFactory;
1817

1918
/** Auto subsystem. */
2019
public class Auto extends Subsystem {
@@ -49,7 +48,7 @@ private Auto() {
4948
new PIDConstants(1.0),
5049
new PIDConstants(1.0),
5150
swerve.maximumTranslationVelocity(),
52-
SwerveFactory.createNorthEastModuleTranslation().getNorm(), // TODO
51+
swerve.driveRadius(),
5352
new ReplanningConfig()),
5453
AllianceFlipHelper::shouldFlip,
5554
swerve);

Diff for: src/main/java/frc/robot/swerve/Swerve.java

+15-45
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,9 @@ public class Swerve extends Subsystem {
7373
.withProportionalGain(0.75) // volts per rotation per second
7474
);
7575

76+
/** Wheel circumference. */
77+
private final double wheelCircumference = Units.inchesToMeters(4.0) * Math.PI;
78+
7679
/** Translation motion profile config. */
7780
private final MotionProfileConfig translationMotionProfileConfig =
7881
new MotionProfileConfig()
@@ -85,10 +88,14 @@ public class Swerve extends Subsystem {
8588

8689
/** Initializes the swerve subsystem and configures swerve hardware. */
8790
private Swerve() {
88-
swerveModules[0] = SwerveFactory.createNorthWestModule(steerConfig, driveConfig);
89-
swerveModules[1] = SwerveFactory.createNorthEastModule(steerConfig, driveConfig);
90-
swerveModules[2] = SwerveFactory.createSouthEastModule(steerConfig, driveConfig);
91-
swerveModules[3] = SwerveFactory.createSouthWestModule(steerConfig, driveConfig);
91+
swerveModules[0] =
92+
SwerveFactory.createNorthWestModule(steerConfig, driveConfig, wheelCircumference);
93+
swerveModules[1] =
94+
SwerveFactory.createNorthEastModule(steerConfig, driveConfig, wheelCircumference);
95+
swerveModules[2] =
96+
SwerveFactory.createSouthEastModule(steerConfig, driveConfig, wheelCircumference);
97+
swerveModules[3] =
98+
SwerveFactory.createSouthWestModule(steerConfig, driveConfig, wheelCircumference);
9299

93100
swerveKinematics =
94101
new SwerveDriveKinematics(
@@ -116,16 +123,6 @@ public void periodic() {}
116123

117124
@Override
118125
public void addToShuffleboard(ShuffleboardTab tab) {
119-
ShuffleboardLayout translationConstants = Telemetry.addColumn(tab, "Translation Constants");
120-
121-
translationConstants.addDouble("Maximum Velocity (mps)", this::maximumTranslationVelocity);
122-
translationConstants.addDouble(
123-
"Maximum Accleration (mpsps)", this::maximumTranslationAcceleration);
124-
125-
ShuffleboardLayout rotationConstants = Telemetry.addColumn(tab, "Rotation Constants");
126-
rotationConstants.addDouble(
127-
"Maximum Velocity (rps)", () -> maximumRotationVelocity().getRotations());
128-
129126
Telemetry.addSwerveModuleStates(tab, "Swerve Module States", this::getModuleStates);
130127
Telemetry.addSwerveModuleStates(tab, "Swerve Module Setpoints", this::getModuleSetpoints);
131128

@@ -234,15 +231,6 @@ public void setSetpoints(SwerveModuleState[] setpoints, boolean lazy) {
234231
}
235232
}
236233

237-
/**
238-
* Returns the motion profile config.
239-
*
240-
* @return the motion profile config.
241-
*/
242-
public MotionProfileConfig translationMotionProfileConfig() {
243-
return translationMotionProfileConfig;
244-
}
245-
246234
/**
247235
* Returns the maximum translation velocity.
248236
*
@@ -253,30 +241,12 @@ public double maximumTranslationVelocity() {
253241
}
254242

255243
/**
256-
* Returns the maximum translation acceleration.
257-
*
258-
* @return the maximum translation acceleration.
259-
*/
260-
public double maximumTranslationAcceleration() {
261-
return translationMotionProfileConfig.maximumAcceleration();
262-
}
263-
264-
/**
265-
* Returns the rotation motion profile config.
266-
*
267-
* @return the rotation motion profile config.
268-
*/
269-
public MotionProfileConfig rotationMotionProfileConfig() {
270-
return rotationMotionProfileConfig;
271-
}
272-
273-
/**
274-
* Returns the maximum rotation velocity.
244+
* Returns the drive radius (distance to the farthest module).
275245
*
276-
* @return the maximum rotation velocity.
246+
* @return the drive readius (distance to the farthest module).
277247
*/
278-
public Rotation2d maximumRotationVelocity() {
279-
return Rotation2d.fromRotations(rotationMotionProfileConfig.maximumVelocity());
248+
public double driveRadius() {
249+
return SwerveFactory.createNorthEastModuleTranslation().getNorm();
280250
}
281251

282252
/**

Diff for: src/main/java/frc/robot/swerve/SwerveFactory.java

+22-10
Original file line numberDiff line numberDiff line change
@@ -27,8 +27,16 @@ public class SwerveFactory {
2727
* @return a swerve module.
2828
*/
2929
private static SwerveModuleIO createModule(
30-
CAN steer, CAN azimuth, CAN drive, MechanismConfig steerConfig, MechanismConfig driveConfig) {
31-
return new SwerveModuleIOCustom(steer, azimuth, drive, steerConfig, driveConfig);
30+
CAN steer,
31+
CAN azimuth,
32+
CAN drive,
33+
MechanismConfig steerConfig,
34+
MechanismConfig driveConfig,
35+
double wheelCircumference) {
36+
return new SwerveModuleIOCustom(
37+
createSteerMotor(steer, azimuth, steerConfig),
38+
createDriveMotor(drive, driveConfig),
39+
wheelCircumference);
3240
}
3341

3442
/**
@@ -37,15 +45,16 @@ private static SwerveModuleIO createModule(
3745
* @return the north west swerve module.
3846
*/
3947
public static SwerveModuleIO createNorthWestModule(
40-
MechanismConfig steerConfig, MechanismConfig driveConfig) {
48+
MechanismConfig steerConfig, MechanismConfig driveConfig, double wheelCircumference) {
4149
return createModule(
4250
new CAN(8, "swerve"),
4351
new CAN(16, "swerve"),
4452
new CAN(24, "swerve"),
4553
steerConfig.withAbsoluteEncoderConfig(
4654
new AbsoluteEncoderConfig()
4755
.withOffset(Rotation2d.fromRotations(-0.084717).unaryMinus())),
48-
driveConfig);
56+
driveConfig,
57+
wheelCircumference);
4958
}
5059

5160
/**
@@ -63,15 +72,16 @@ public static Translation2d createNorthWestModuleTranslation() {
6372
* @return the north east swerve module.
6473
*/
6574
public static SwerveModuleIO createNorthEastModule(
66-
MechanismConfig steerConfig, MechanismConfig driveConfig) {
75+
MechanismConfig steerConfig, MechanismConfig driveConfig, double wheelCircumference) {
6776
return createModule(
6877
new CAN(16, "swerve"),
6978
new CAN(18, "swerve"),
7079
new CAN(30, "swerve"),
7180
steerConfig.withAbsoluteEncoderConfig(
7281
new AbsoluteEncoderConfig()
7382
.withOffset(Rotation2d.fromRotations(0.196777).unaryMinus())),
74-
driveConfig);
83+
driveConfig,
84+
wheelCircumference);
7585
}
7686

7787
/**
@@ -89,15 +99,16 @@ public static Translation2d createNorthEastModuleTranslation() {
8999
* @return the south east swerve module.
90100
*/
91101
public static SwerveModuleIO createSouthEastModule(
92-
MechanismConfig steerConfig, MechanismConfig driveConfig) {
102+
MechanismConfig steerConfig, MechanismConfig driveConfig, double wheelCircumference) {
93103
return createModule(
94104
new CAN(12, "swerve"),
95105
new CAN(22, "swerve"),
96106
new CAN(26, "swerve"),
97107
steerConfig.withAbsoluteEncoderConfig(
98108
new AbsoluteEncoderConfig()
99109
.withOffset(Rotation2d.fromRotations(0.276611).unaryMinus())),
100-
driveConfig);
110+
driveConfig,
111+
wheelCircumference);
101112
}
102113

103114
/**
@@ -115,15 +126,16 @@ public static Translation2d createSouthEastModuleTranslation() {
115126
* @return the south west swerve module.
116127
*/
117128
public static SwerveModuleIO createSouthWestModule(
118-
MechanismConfig steerConfig, MechanismConfig driveConfig) {
129+
MechanismConfig steerConfig, MechanismConfig driveConfig, double wheelCircumference) {
119130
return createModule(
120131
new CAN(10, "swerve"),
121132
new CAN(20, "swerve"),
122133
new CAN(28, "swerve"),
123134
steerConfig.withAbsoluteEncoderConfig(
124135
new AbsoluteEncoderConfig()
125136
.withOffset(Rotation2d.fromRotations(0.223145).unaryMinus())),
126-
driveConfig);
137+
driveConfig,
138+
wheelCircumference);
127139
}
128140

129141
/**

0 commit comments

Comments
 (0)