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

Commit 7716544

Browse files
committed
refactor(swerve): Do away with module config.
1 parent ee05045 commit 7716544

File tree

7 files changed

+108
-110
lines changed

7 files changed

+108
-110
lines changed

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

+2-1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
import frc.robot.superstructure.Superstructure;
1616
import frc.robot.swerve.Swerve;
1717
import frc.robot.swerve.SwerveConstants;
18+
import frc.robot.swerve.SwerveFactory;
1819

1920
/** Auto subsystem. */
2021
public class Auto extends Subsystem {
@@ -49,7 +50,7 @@ private Auto() {
4950
new PIDConstants(1.0),
5051
new PIDConstants(1.0),
5152
SwerveConstants.MAXIMUM_SPEED,
52-
SwerveConstants.NORTH_EAST_MODULE_CONFIG.position().getNorm(),
53+
SwerveFactory.createNorthEastModuleTranslation().getNorm(), // TODO
5354
new ReplanningConfig()),
5455
AllianceFlipHelper::shouldFlip,
5556
swerve);

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

+8-8
Original file line numberDiff line numberDiff line change
@@ -27,17 +27,17 @@ public class Swerve extends Subsystem {
2727

2828
/** Initializes the swerve subsystem and configures swerve hardware. */
2929
private Swerve() {
30-
swerveModules[0] = SwerveFactory.createModule(SwerveConstants.NORTH_WEST_MODULE_CONFIG);
31-
swerveModules[1] = SwerveFactory.createModule(SwerveConstants.NORTH_EAST_MODULE_CONFIG);
32-
swerveModules[2] = SwerveFactory.createModule(SwerveConstants.SOUTH_EAST_MODULE_CONFIG);
33-
swerveModules[3] = SwerveFactory.createModule(SwerveConstants.SOUTH_WEST_MODULE_CONFIG);
30+
swerveModules[0] = SwerveFactory.createNorthWestModule();
31+
swerveModules[1] = SwerveFactory.createNorthEastModule();
32+
swerveModules[2] = SwerveFactory.createSouthEastModule();
33+
swerveModules[3] = SwerveFactory.createSouthWestModule();
3434

3535
swerveKinematics =
3636
new SwerveDriveKinematics(
37-
SwerveConstants.NORTH_WEST_MODULE_CONFIG.position(),
38-
SwerveConstants.NORTH_EAST_MODULE_CONFIG.position(),
39-
SwerveConstants.SOUTH_EAST_MODULE_CONFIG.position(),
40-
SwerveConstants.SOUTH_WEST_MODULE_CONFIG.position());
37+
SwerveFactory.createNorthWestModuleTranslation(),
38+
SwerveFactory.createNorthEastModuleTranslation(),
39+
SwerveFactory.createSouthEastModuleTranslation(),
40+
SwerveFactory.createSouthWestModuleTranslation());
4141
}
4242

4343
/**

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

-32
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,6 @@
11
package frc.robot.swerve;
22

33
import edu.wpi.first.math.geometry.Rotation2d;
4-
import edu.wpi.first.math.geometry.Translation2d;
54
import edu.wpi.first.math.util.Units;
65
import frc.lib.config.FeedbackControllerConfig;
76
import frc.lib.config.FeedforwardControllerConfig;
@@ -32,37 +31,6 @@ public static class MK4iConstants {
3231
/** Module Y offset in meters. */
3332
public static final double Y_OFFSET = Units.inchesToMeters(10.375);
3433

35-
/** Swerve's CAN bus. */
36-
public static final String SWERVE_BUS = "swerve";
37-
38-
/** Module configuration for the north west swerve module. */
39-
public static final SwerveModuleConfig NORTH_WEST_MODULE_CONFIG =
40-
new SwerveModuleConfig(
41-
new SwerveModuleCAN(16, 8, 24, SWERVE_BUS),
42-
new Translation2d(X_OFFSET, Y_OFFSET),
43-
Rotation2d.fromRotations(-0.084717).unaryMinus());
44-
45-
/** Module configuration for the north east swerve module. */
46-
public static final SwerveModuleConfig NORTH_EAST_MODULE_CONFIG =
47-
new SwerveModuleConfig(
48-
new SwerveModuleCAN(18, 16, 30, SWERVE_BUS),
49-
new Translation2d(X_OFFSET, -Y_OFFSET),
50-
Rotation2d.fromRotations(0.196777).unaryMinus());
51-
52-
/** Module configuration for the south east swerve module. */
53-
public static final SwerveModuleConfig SOUTH_EAST_MODULE_CONFIG =
54-
new SwerveModuleConfig(
55-
new SwerveModuleCAN(22, 12, 26, SWERVE_BUS),
56-
new Translation2d(-X_OFFSET, -Y_OFFSET),
57-
Rotation2d.fromRotations(0.276611).unaryMinus());
58-
59-
/** Module configuration for the south west swerve module. */
60-
public static final SwerveModuleConfig SOUTH_WEST_MODULE_CONFIG =
61-
new SwerveModuleConfig(
62-
new SwerveModuleCAN(20, 10, 28, SWERVE_BUS),
63-
new Translation2d(-X_OFFSET, Y_OFFSET),
64-
Rotation2d.fromRotations(-0.276855).plus(Rotation2d.fromDegrees(180)).unaryMinus());
65-
6634
/** Maximum speed in meters per second. */
6735
public static final double MAXIMUM_SPEED = 4.5;
6836

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

+94-5
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
package frc.robot.swerve;
22

33
import edu.wpi.first.math.geometry.Rotation2d;
4+
import edu.wpi.first.math.geometry.Translation2d;
5+
import edu.wpi.first.math.util.Units;
46
import frc.lib.CAN;
57
import frc.lib.config.AbsoluteEncoderConfig;
68
import frc.lib.controller.PositionControllerIO;
@@ -13,16 +15,104 @@
1315
import frc.robot.RobotConstants;
1416
import frc.robot.RobotConstants.Subsystem;
1517

16-
/** Helper class for creating hardware for the swerve subsystem. */
18+
/** Factory for creating swerve subsystem hardware. */
1719
public class SwerveFactory {
1820

1921
/**
2022
* Creates a swerve module.
2123
*
2224
* @return a swerve module.
2325
*/
24-
public static SwerveModuleIO createModule(SwerveModuleConfig config) {
25-
return new SwerveModuleIOCustom(config);
26+
private static SwerveModuleIO createModule(CAN steer, CAN azimuth, CAN drive, Rotation2d offset) {
27+
return new SwerveModuleIOCustom(steer, azimuth, drive, offset);
28+
}
29+
30+
/**
31+
* creates the north west swerve module.
32+
*
33+
* @return the north west swerve module.
34+
*/
35+
public static SwerveModuleIO createNorthWestModule() {
36+
return createModule(
37+
new CAN(8, "swerve"),
38+
new CAN(16, "swerve"),
39+
new CAN(24, "swerve"),
40+
Rotation2d.fromRotations(-0.084717).unaryMinus());
41+
}
42+
43+
/**
44+
* Creates the north west swerve module translation.
45+
*
46+
* @return the north west swerve module translation.
47+
*/
48+
public static Translation2d createNorthWestModuleTranslation() {
49+
return new Translation2d(Units.inchesToMeters(10.375), Units.inchesToMeters(10.375));
50+
}
51+
52+
/**
53+
* creates the north east swerve module.
54+
*
55+
* @return the north east swerve module.
56+
*/
57+
public static SwerveModuleIO createNorthEastModule() {
58+
return createModule(
59+
new CAN(16, "swerve"),
60+
new CAN(18, "swerve"),
61+
new CAN(30, "swerve"),
62+
Rotation2d.fromRotations(0.196777).unaryMinus());
63+
}
64+
65+
/**
66+
* Creates the north east swerve module translation.
67+
*
68+
* @return the north east swerve module translation.
69+
*/
70+
public static Translation2d createNorthEastModuleTranslation() {
71+
return new Translation2d(Units.inchesToMeters(10.375), Units.inchesToMeters(-10.375));
72+
}
73+
74+
/**
75+
* creates the south east swerve module.
76+
*
77+
* @return the south east swerve module.
78+
*/
79+
public static SwerveModuleIO createSouthEastModule() {
80+
return createModule(
81+
new CAN(12, "swerve"),
82+
new CAN(22, "swerve"),
83+
new CAN(26, "swerve"),
84+
Rotation2d.fromRotations(0.276611).unaryMinus());
85+
}
86+
87+
/**
88+
* Creates the south east swerve module translation.
89+
*
90+
* @return the south east swerve module translation.
91+
*/
92+
public static Translation2d createSouthEastModuleTranslation() {
93+
return new Translation2d(Units.inchesToMeters(-10.375), Units.inchesToMeters(-10.375));
94+
}
95+
96+
/**
97+
* creates the south west swerve module.
98+
*
99+
* @return the south west swerve module.
100+
*/
101+
public static SwerveModuleIO createSouthWestModule() {
102+
return createModule(
103+
new CAN(10, "swerve"),
104+
new CAN(20, "swerve"),
105+
new CAN(28, "drive"),
106+
Rotation2d.fromRotations(0.223145).unaryMinus());
107+
}
108+
109+
/**
110+
* Creates the south west swerve module translation.
111+
*
112+
* @return the south west swerve module translation.
113+
*/
114+
public static Translation2d createSouthWestModuleTranslation() {
115+
return new Translation2d(Units.inchesToMeters(-10.375), Units.inchesToMeters(10.375));
26116
}
27117

28118
/**
@@ -49,8 +139,7 @@ public static PositionControllerIO createSteerMotor(CAN steer, CAN azimuth, Rota
49139
*/
50140
public static VelocityControllerIO createDriveMotor(CAN drive) {
51141
if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.SWERVE))
52-
return new VelocityControllerIOTalonFXPIDF(
53-
drive, SwerveConstants.DRIVE_CONFIG, false);
142+
return new VelocityControllerIOTalonFXPIDF(drive, SwerveConstants.DRIVE_CONFIG, false);
54143

55144
return new VelocityControllerIOSim();
56145
}

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

-33
This file was deleted.

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

-23
This file was deleted.

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

+4-8
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
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;
78
import frc.lib.controller.PositionControllerIO;
89
import frc.lib.controller.PositionControllerIO.PositionControllerIOValues;
910
import frc.lib.controller.VelocityControllerIO;
@@ -28,16 +29,11 @@ public class SwerveModuleIOCustom implements SwerveModuleIO {
2829
/** Module setpoint */
2930
private SwerveModuleState setpoint;
3031

31-
/**
32-
* Creates a custom swerve module.
33-
*
34-
* @param config the swerve module's configuration.
35-
*/
36-
public SwerveModuleIOCustom(SwerveModuleConfig config) {
37-
steerMotor = SwerveFactory.createSteerMotor(config.moduleCAN().steer(), config.moduleCAN().azimuth(), config.offset());
32+
public SwerveModuleIOCustom(CAN steer, CAN azimuth, CAN drive, Rotation2d offset) {
33+
steerMotor = SwerveFactory.createSteerMotor(steer, azimuth, offset);
3834
steerMotor.configure();
3935

40-
driveMotor = SwerveFactory.createDriveMotor(config.moduleCAN().drive());
36+
driveMotor = SwerveFactory.createDriveMotor(drive);
4137
driveMotor.configure();
4238

4339
setpoint = new SwerveModuleState();

0 commit comments

Comments
 (0)