Skip to content

Commit f03369e

Browse files
committed
replaced deprecated methods
1 parent 9a758cb commit f03369e

File tree

5 files changed

+23
-19
lines changed

5 files changed

+23
-19
lines changed

src/main/java/org/carlmontrobotics/lib199/MotorControllerFactory.java

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@
1414

1515
import com.ctre.phoenix.motorcontrol.NeutralMode;
1616
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
17+
import com.revrobotics.PersistMode;
18+
import com.revrobotics.ResetMode;
1719
import com.revrobotics.spark.SparkBase;
1820
import com.revrobotics.spark.SparkFlex;
1921
import com.revrobotics.spark.SparkLowLevel;
@@ -78,8 +80,8 @@ public static SparkMax createSparkMax(int id, MotorConfig motorConfig, SparkBase
7880
}
7981
MotorErrors.reportError(spark.configure(
8082
config,
81-
SparkBase.ResetMode.kResetSafeParameters,
82-
SparkBase.PersistMode.kPersistParameters
83+
ResetMode.kResetSafeParameters,
84+
PersistMode.kPersistParameters
8385
));
8486
MotorErrors.reportSparkTemp(spark, motorConfig.temperatureLimitCelsius);
8587
MotorErrors.checkSparkErrors(spark);
@@ -109,8 +111,8 @@ public static SparkFlex createSparkFlex(int id, MotorConfig motorConfig, SparkBa
109111
}
110112
MotorErrors.reportError(spark.configure(
111113
config,
112-
SparkBase.ResetMode.kResetSafeParameters,
113-
SparkBase.PersistMode.kPersistParameters
114+
ResetMode.kResetSafeParameters,
115+
PersistMode.kPersistParameters
114116
));
115117

116118
MotorErrors.reportSparkTemp(spark, motorConfig.temperatureLimitCelsius);

src/main/java/org/carlmontrobotics/lib199/MotorErrors.java

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,9 @@
66
import java.util.concurrent.ConcurrentSkipListMap;
77

88
import com.ctre.phoenix.ErrorCode;
9+
import com.revrobotics.PersistMode;
910
import com.revrobotics.REVLibError;
11+
import com.revrobotics.ResetMode;
1012
import com.revrobotics.spark.SparkBase;
1113
import com.revrobotics.spark.SparkBase.Faults;
1214
import com.revrobotics.spark.SparkFlex;
@@ -187,14 +189,14 @@ private static void reportSparkTemp(int port, SparkBase spark) {
187189
case SPARK_MAX:
188190
spark.configure(
189191
OVERHEAT_MAX_CONFIG,
190-
SparkBase.ResetMode.kNoResetSafeParameters,
191-
SparkBase.PersistMode.kNoPersistParameters);
192+
ResetMode.kNoResetSafeParameters,
193+
PersistMode.kNoPersistParameters);
192194
break;
193195
case SPARK_FLEX:
194196
spark.configure(
195197
OVERHEAT_FLEX_CONFIG,
196-
SparkBase.ResetMode.kNoResetSafeParameters,
197-
SparkBase.PersistMode.kNoPersistParameters);
198+
ResetMode.kNoResetSafeParameters,
199+
PersistMode.kNoPersistParameters);
198200
break;
199201
default:
200202
System.err.println("Unknown spark :(");

src/main/java/org/carlmontrobotics/lib199/SparkVelocityPIDController.java

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,8 @@
44
import com.revrobotics.spark.ClosedLoopSlot;
55
import com.revrobotics.spark.SparkBase;
66
import com.revrobotics.spark.SparkBase.ControlType;
7-
import com.revrobotics.spark.SparkBase.PersistMode;
8-
import com.revrobotics.spark.SparkBase.ResetMode;
7+
import com.revrobotics.PersistMode;
8+
import com.revrobotics.ResetMode;
99
import com.revrobotics.spark.SparkClosedLoopController;
1010
import com.revrobotics.spark.config.ClosedLoopConfig;
1111
import edu.wpi.first.util.sendable.Sendable;
@@ -36,12 +36,12 @@ public SparkVelocityPIDController(String name, SparkBase spark, double defaultP,
3636
this.currentI = defaultI,
3737
this.currentD = defaultD
3838
)),
39-
SparkBase.ResetMode.kNoResetSafeParameters,//we only want to change pid params
40-
SparkBase.PersistMode.kNoPersistParameters);
39+
ResetMode.kNoResetSafeParameters,//we only want to change pid params
40+
PersistMode.kNoPersistParameters);
4141
this.kS = kS;
4242
this.kV = kV;
4343

44-
pidController.setReference(targetSpeed, ControlType.kVelocity, ClosedLoopSlot.kSlot0, calculateFF(targetSpeed));
44+
pidController.setSetpoint(targetSpeed, ControlType.kVelocity, ClosedLoopSlot.kSlot0, calculateFF(targetSpeed));
4545

4646
SendableRegistry.addLW(this, "SparkVelocityPIDController", spark.getDeviceId());
4747
}
@@ -65,7 +65,7 @@ public double getTargetSpeed() {
6565
public void setTargetSpeed(double targetSpeed) {
6666
if(targetSpeed == this.targetSpeed) return;
6767
this.targetSpeed = targetSpeed;
68-
pidController.setReference(targetSpeed, ControlType.kVelocity, ClosedLoopSlot.kSlot0, calculateFF(targetSpeed));
68+
pidController.setSetpoint(targetSpeed, ControlType.kVelocity, ClosedLoopSlot.kSlot0, calculateFF(targetSpeed));
6969
}
7070

7171
public double getTolerance() {
@@ -99,7 +99,7 @@ public void initSendable(SendableBuilder builder) {
9999
});
100100
builder.addDoubleProperty("Target Speed", () -> targetSpeed, newSpeed -> {
101101
if(newSpeed == targetSpeed) return;
102-
pidController.setReference(newSpeed, ControlType.kVelocity, ClosedLoopSlot.kSlot0, calculateFF(newSpeed));
102+
pidController.setSetpoint(newSpeed, ControlType.kVelocity, ClosedLoopSlot.kSlot0, calculateFF(newSpeed));
103103
targetSpeed = newSpeed;
104104
});
105105
builder.addDoubleProperty("Tolerance", () -> tolerance, newTolerance -> tolerance = newTolerance);

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,8 +9,8 @@
99
import com.ctre.phoenix6.configs.CANcoderConfiguration;
1010
import com.ctre.phoenix6.hardware.CANcoder;
1111
import com.revrobotics.spark.SparkBase;
12-
import com.revrobotics.spark.SparkBase.PersistMode;
13-
import com.revrobotics.spark.SparkBase.ResetMode;
12+
import com.revrobotics.PersistMode;
13+
import com.revrobotics.ResetMode;
1414
import com.revrobotics.spark.config.SparkBaseConfig;
1515
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
1616
import com.revrobotics.spark.config.SparkBaseConfigAccessor;

src/test/java/org/carlmontrobotics/lib199/safeMode/SafeModeCommandsTest.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ public void testCommand(Function<Command, Command> constructor, boolean isSafe,
4343
loggingCommand.reset();
4444

4545
SafeMode.enable();
46-
command.schedule();
46+
CommandScheduler.getInstance().schedule(command);
4747
CommandScheduler.getInstance().run();
4848
if (isSafe || staysEnabled)
4949
assertTrue(command.isScheduled());
@@ -56,7 +56,7 @@ public void testCommand(Function<Command, Command> constructor, boolean isSafe,
5656
assertEquals(isSafe ? 1 : 0, loggingCommand.getExecuteCount());
5757

5858
SafeMode.disable();
59-
command.schedule();
59+
CommandScheduler.getInstance().schedule(command);
6060
CommandScheduler.getInstance().run();
6161
if (!isSafe || staysEnabled)
6262
assertTrue(command.isScheduled());

0 commit comments

Comments
 (0)