Skip to content

Commit 88c7b6e

Browse files
committed
made swerverModule work with any neo motor
1 parent cf50401 commit 88c7b6e

File tree

1 file changed

+46
-8
lines changed

1 file changed

+46
-8
lines changed

src/main/java/org/carlmontrobotics/lib199/swerve/SwerveModule.java

Lines changed: 46 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -6,16 +6,18 @@
66

77
import java.util.function.Supplier;
88

9+
import org.carlmontrobotics.lib199.SparkMotorType;
910
import org.mockito.internal.reporting.SmartPrinter;
1011

1112
import com.ctre.phoenix6.configs.CANcoderConfiguration;
1213
import com.ctre.phoenix6.hardware.CANcoder;
13-
import com.revrobotics.spark.SparkMax;
14+
import com.revrobotics.spark.SparkBase;
1415
import com.revrobotics.spark.SparkBase.PersistMode;
1516
import com.revrobotics.spark.SparkBase.ResetMode;
1617
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
1718
import com.revrobotics.spark.config.SparkBaseConfig;
1819
import com.revrobotics.spark.config.SparkMaxConfig;
20+
import com.revrobotics.spark.config.SparkFlexConfig;
1921

2022
import edu.wpi.first.math.MathUtil;
2123
import edu.wpi.first.math.controller.PIDController;
@@ -45,11 +47,11 @@ public class SwerveModule implements Sendable {
4547
public enum ModuleType {FL, FR, BL, BR};
4648

4749
private SwerveConfig config;
48-
private SparkMaxConfig turnConfig = new SparkMaxConfig();
49-
private SparkMaxConfig driveConfig = new SparkMaxConfig();
50+
private SparkBaseConfig turnConfig;
51+
private SparkBaseConfig driveConfig;
5052

5153
private ModuleType type;
52-
private SparkMax drive, turn;
54+
private SparkBase drive, turn;
5355
private CANcoder turnEncoder;
5456
private PIDController drivePIDController;
5557
private ProfiledPIDController turnPIDController;
@@ -70,9 +72,30 @@ public enum ModuleType {FL, FR, BL, BR};
7072
private static final int NEO_HALL_COUNTS_PER_REV = 42;
7173
private static final int ENCODER_POSITION_PERIOD_MS = 20;
7274
private int encoderAverageDepth = 2;
75+
76+
SparkMotorType driveMotorType;
77+
SparkMotorType turnMotorType;
7378

74-
public SwerveModule(SwerveConfig config, ModuleType type, SparkMax drive, SparkMax turn, CANcoder turnEncoder,
79+
public SwerveModule(SwerveConfig config, ModuleType type, SparkBase drive, SparkBase turn, SparkMotorType driveMotorType, SparkMotorType turnMotorType, CANcoder turnEncoder,
7580
int arrIndex, Supplier<Float> pitchDegSupplier, Supplier<Float> rollDegSupplier) {
81+
this.driveMotorType = driveMotorType;
82+
this.turnMotorType = turnMotorType;
83+
switch(driveMotorType) {
84+
case NEO, NEO550, NEO_2, SOLO_VORTEX:
85+
driveConfig = new SparkMaxConfig();
86+
break;
87+
case VORTEX:
88+
driveConfig = new SparkFlexConfig();
89+
break;
90+
}
91+
switch(turnMotorType) {
92+
case NEO, NEO550, NEO_2, SOLO_VORTEX:
93+
turnConfig = new SparkMaxConfig();
94+
break;
95+
case VORTEX:
96+
turnConfig = new SparkFlexConfig();
97+
break;
98+
}
7699
//SmartDashboard.putNumber("Target Angle (deg)", 0.0);
77100
String moduleString = type.toString();
78101
this.timer = new Timer();
@@ -441,15 +464,30 @@ public void toggleMode() {
441464

442465
public void brake() {
443466
idleMode = IdleMode.kBrake;
444-
SparkBaseConfig config = new SparkMaxConfig().idleMode(IdleMode.kBrake);
467+
SparkBaseConfig config = null;
468+
switch(driveMotorType){
469+
case NEO, NEO550, NEO_2, SOLO_VORTEX:
470+
config = new SparkMaxConfig().idleMode(IdleMode.kBrake);
471+
break;
472+
case VORTEX:
473+
config = new SparkFlexConfig().idleMode(IdleMode.kBrake);
474+
break;
475+
}
445476
drive.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
446477
turn .configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
447478
}
448479

449480
public void coast() {
450481
idleMode = IdleMode.kCoast;
451-
idleMode = IdleMode.kCoast;
452-
SparkBaseConfig config = new SparkMaxConfig().idleMode(IdleMode.kCoast);
482+
SparkBaseConfig config = null;
483+
switch(driveMotorType){
484+
case NEO, NEO550, NEO_2, SOLO_VORTEX:
485+
config = new SparkMaxConfig().idleMode(IdleMode.kCoast);
486+
break;
487+
case VORTEX:
488+
config = new SparkFlexConfig().idleMode(IdleMode.kCoast);
489+
break;
490+
}
453491
drive.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
454492
turn .configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
455493
}

0 commit comments

Comments
 (0)