1
1
package frc .robot .swerve ;
2
2
3
3
import edu .wpi .first .math .geometry .Rotation2d ;
4
+ import edu .wpi .first .math .geometry .Translation2d ;
5
+ import edu .wpi .first .math .util .Units ;
4
6
import frc .lib .CAN ;
5
7
import frc .lib .config .AbsoluteEncoderConfig ;
6
8
import frc .lib .controller .PositionControllerIO ;
13
15
import frc .robot .RobotConstants ;
14
16
import frc .robot .RobotConstants .Subsystem ;
15
17
16
- /** Helper class for creating hardware for the swerve subsystem. */
18
+ /** Factory for creating swerve subsystem hardware . */
17
19
public class SwerveFactory {
18
20
19
21
/**
20
22
* Creates a swerve module.
21
23
*
22
24
* @return a swerve module.
23
25
*/
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 ));
26
116
}
27
117
28
118
/**
@@ -49,8 +139,7 @@ public static PositionControllerIO createSteerMotor(CAN steer, CAN azimuth, Rota
49
139
*/
50
140
public static VelocityControllerIO createDriveMotor (CAN drive ) {
51
141
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 );
54
143
55
144
return new VelocityControllerIOSim ();
56
145
}
0 commit comments