Skip to content

Commit d8512e6

Browse files
committed
made drive motors use spark flexes
1 parent 244a436 commit d8512e6

File tree

1 file changed

+10
-9
lines changed

1 file changed

+10
-9
lines changed

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

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -11,11 +11,13 @@
1111
// import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue;
1212
import com.ctre.phoenix6.configs.CANcoderConfiguration;
1313
import com.ctre.phoenix6.hardware.CANcoder;
14+
import com.revrobotics.spark.SparkFlex;
1415
import com.revrobotics.spark.SparkMax;
1516
import com.revrobotics.spark.SparkBase.PersistMode;
1617
import com.revrobotics.spark.SparkBase.ResetMode;
1718
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
1819
import com.revrobotics.spark.config.SparkBaseConfig;
20+
import com.revrobotics.spark.config.SparkFlexConfig;
1921
import com.revrobotics.spark.config.SparkMaxConfig;
2022

2123
import edu.wpi.first.math.MathUtil;
@@ -47,10 +49,11 @@ public enum ModuleType {FL, FR, BL, BR};
4749

4850
private SwerveConfig config;
4951
private SparkMaxConfig turnConfig = new SparkMaxConfig();
50-
private SparkMaxConfig driveConfig = new SparkMaxConfig();
52+
private SparkFlexConfig driveConfig = new SparkFlexConfig();
5153

5254
private ModuleType type;
53-
private SparkMax drive, turn;
55+
private SparkFlex drive;
56+
private SparkMax turn;
5457
private CANcoder turnEncoder;
5558
private PIDController drivePIDController;
5659
private ProfiledPIDController turnPIDController;
@@ -65,7 +68,7 @@ public enum ModuleType {FL, FR, BL, BR};
6568

6669
private double turnSpeedCorrectionVolts, turnFFVolts, turnVolts;
6770
private double maxTurnVelocityWithoutTippingRps;
68-
public SwerveModule(SwerveConfig config, ModuleType type, SparkMax drive, SparkMax turn, CANcoder turnEncoder,
71+
public SwerveModule(SwerveConfig config, ModuleType type, SparkFlex drive, SparkMax turn, CANcoder turnEncoder,
6972
int arrIndex, Supplier<Float> pitchDegSupplier, Supplier<Float> rollDegSupplier) {
7073
//SmartDashboard.putNumber("Target Angle (deg)", 0.0);
7174
String moduleString = type.toString();
@@ -434,15 +437,13 @@ public void toggleMode() {
434437
}
435438

436439
public void brake() {
437-
SparkBaseConfig config = new SparkMaxConfig().idleMode(IdleMode.kBrake);
438-
drive.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
439-
turn .configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
440+
drive.configure(new SparkFlexConfig().idleMode(IdleMode.kBrake), ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
441+
turn .configure(new SparkMaxConfig().idleMode(IdleMode.kBrake), ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
440442
}
441443

442444
public void coast() {
443-
SparkBaseConfig config = new SparkMaxConfig().idleMode(IdleMode.kCoast);
444-
drive.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
445-
turn .configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
445+
drive.configure(new SparkFlexConfig().idleMode(IdleMode.kCoast), ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
446+
turn .configure(new SparkMaxConfig().idleMode(IdleMode.kCoast), ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
446447
}
447448

448449
/**

0 commit comments

Comments
 (0)