Skip to content

Commit 0155542

Browse files
committed
Merge branch '2025' into 2026
2 parents 2fa2381 + aed08b5 commit 0155542

15 files changed

Lines changed: 161 additions & 228 deletions

build.gradle

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -126,8 +126,8 @@ javadoc {
126126
links 'https://github.wpilib.org/allwpilib/docs/release/java/'
127127
links 'https://www.kauailabs.com/public_files/navx-mxp/apidocs/java/'
128128
links 'https://pathplanner.dev/api/java/'
129-
links 'https://api.ctr-electronics.com/phoenix/release/java/'
130-
links 'https://api.ctr-electronics.com/phoenix6/release/java/'
129+
links 'https://api.ctr-electronics.com/phoenix/stable/java/'
130+
links 'https://api.ctr-electronics.com/phoenix6/stable/java/'
131131
links 'https://www.playingwithfusion.com/frc/2022/javadoc/'
132132
links 'https://codedocs.revrobotics.com/java/'
133133
}

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ public static SparkMax createSparkMax(int id, MotorConfig motorConfig, SparkBase
7979
MotorErrors.reportError(spark.configure(
8080
config,
8181
SparkBase.ResetMode.kResetSafeParameters,
82-
SparkBase.PersistMode.kNoPersistParameters
82+
SparkBase.PersistMode.kPersistParameters
8383
));
8484
MotorErrors.reportSparkTemp(spark, motorConfig.temperatureLimitCelsius);
8585
MotorErrors.checkSparkErrors(spark);
@@ -110,7 +110,7 @@ public static SparkFlex createSparkFlex(int id, MotorConfig motorConfig, SparkBa
110110
MotorErrors.reportError(spark.configure(
111111
config,
112112
SparkBase.ResetMode.kResetSafeParameters,
113-
SparkBase.PersistMode.kNoPersistParameters
113+
SparkBase.PersistMode.kPersistParameters
114114
));
115115

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

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

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

88
import com.ctre.phoenix.ErrorCode;
9+
import com.revrobotics.REVLibError;
910
import com.revrobotics.spark.SparkBase;
11+
import com.revrobotics.spark.SparkBase.Faults;
1012
import com.revrobotics.spark.SparkFlex;
11-
import com.revrobotics.spark.SparkLowLevel;
1213
import com.revrobotics.spark.SparkMax;
13-
import com.revrobotics.spark.SparkBase.Faults;
1414
import com.revrobotics.spark.config.SparkBaseConfig;
1515
import com.revrobotics.spark.config.SparkFlexConfig;
1616
import com.revrobotics.spark.config.SparkMaxConfig;
17-
import com.revrobotics.REVLibError;
18-
1917
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
2018

21-
import org.carlmontrobotics.lib199.MotorControllerFactory;
22-
2319
public final class MotorErrors {
2420

2521
private static final Map<Integer, SparkBase> temperatureSparks = new ConcurrentSkipListMap<>();
@@ -30,8 +26,8 @@ public final class MotorErrors {
3026
private static final Map<SparkBase, Faults> stickyFlags = new ConcurrentSkipListMap<>(
3127
(spark1, spark2) -> (spark1.getDeviceId() - spark2.getDeviceId()));
3228

33-
private static final SparkBaseConfig OVERHEAT_MAX_CONFIG = new SparkMaxConfig().smartCurrentLimit(1);
34-
private static final SparkBaseConfig OVERHEAT_FLEX_CONFIG = new SparkFlexConfig().smartCurrentLimit(1);
29+
private static final SparkBaseConfig OVERHEAT_MAX_CONFIG = new SparkMaxConfig().smartCurrentLimit(1);
30+
private static final SparkBaseConfig OVERHEAT_FLEX_CONFIG = new SparkFlexConfig().smartCurrentLimit(1);
3531

3632

3733
public static final int kOverheatTripCount = 5;
@@ -80,7 +76,7 @@ public static void checkSparkErrors(SparkBase spark) {
8076
// short faults = spark.getFaults();
8177
Faults faults = spark.getFaults();
8278
Faults stickyFaults = spark.getStickyFaults();
83-
Faults prevFaults = flags.getOrDefault(spark, null);
79+
Faults prevFaults = flags.getOrDefault(spark, null);
8480
Faults prevStickyFaults = stickyFlags.getOrDefault(spark, null);
8581

8682
if (spark.hasActiveFault() && prevFaults!=null && prevFaults.rawBits != faults.rawBits) {

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

Lines changed: 4 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,13 @@
11
package org.carlmontrobotics.lib199;
22

3-
import com.revrobotics.spark.SparkBase;
4-
import com.revrobotics.spark.config.ClosedLoopConfig;
5-
import com.revrobotics.spark.config.SparkBaseConfig;
6-
import com.revrobotics.spark.config.SparkMaxConfig;
73
import com.revrobotics.RelativeEncoder;
84
import com.revrobotics.spark.ClosedLoopSlot;
95
import com.revrobotics.spark.SparkBase;
106
import com.revrobotics.spark.SparkBase.ControlType;
117
import com.revrobotics.spark.SparkBase.PersistMode;
128
import com.revrobotics.spark.SparkBase.ResetMode;
139
import com.revrobotics.spark.SparkClosedLoopController;
14-
10+
import com.revrobotics.spark.config.ClosedLoopConfig;
1511
import edu.wpi.first.util.sendable.Sendable;
1612
import edu.wpi.first.util.sendable.SendableBuilder;
1713
import edu.wpi.first.util.sendable.SendableRegistry;
@@ -33,8 +29,8 @@ public SparkVelocityPIDController(String name, SparkBase spark, double defaultP,
3329
this.name = name;
3430
this.targetSpeed = targetSpeed;
3531
this.tolerance = tolerance;
36-
37-
spark.configure(MotorControllerFactory.sparkConfig(MotorConfig.NEO).apply(
32+
33+
spark.configure(MotorControllerType.getMotorControllerType(spark).createConfig().apply(
3834
new ClosedLoopConfig().pid(
3935
this.currentP = defaultP,
4036
this.currentI = defaultI,
@@ -85,7 +81,7 @@ public double calculateFF(double velocity) {
8581
}
8682

8783
private void instantClosedLoopConfig(ClosedLoopConfig clConfig) {
88-
spark.configure(MotorControllerFactory.sparkConfig(MotorConfig.NEO).apply(clConfig), ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
84+
spark.configure(MotorControllerType.getMotorControllerType(spark).createConfig().apply(clConfig), ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
8985
}
9086

9187
@Override

src/main/java/org/carlmontrobotics/lib199/sim/MockSparkBase.java

Lines changed: 13 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -2,34 +2,27 @@
22

33
import java.util.concurrent.ConcurrentHashMap;
44

5-
import org.carlmontrobotics.lib199.Lib199Subsystem;
6-
import org.carlmontrobotics.lib199.Mocks;
7-
import org.carlmontrobotics.lib199.REVLibErrorAnswer;
8-
9-
import com.revrobotics.spark.config.ClosedLoopConfig;
10-
import com.revrobotics.spark.config.SparkMaxConfig;
11-
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
12-
import com.revrobotics.spark.SparkClosedLoopController;
13-
import com.revrobotics.spark.SparkFlex;
14-
import com.revrobotics.spark.SparkLowLevel;
15-
import com.revrobotics.spark.SparkLowLevel.MotorType;
16-
import com.revrobotics.spark.SparkMax;
175
import com.revrobotics.REVLibError;
186
import com.revrobotics.RelativeEncoder;
7+
import com.revrobotics.sim.SparkAbsoluteEncoderSim;
198
import com.revrobotics.sim.SparkAnalogSensorSim;
209
import com.revrobotics.sim.SparkMaxAlternateEncoderSim;
21-
import com.revrobotics.sim.SparkAbsoluteEncoderSim;
2210
import com.revrobotics.spark.SparkAbsoluteEncoder;
23-
import com.revrobotics.spark.SparkMaxAlternateEncoder;
2411
import com.revrobotics.spark.SparkAnalogSensor;
2512
import com.revrobotics.spark.SparkBase;
26-
import com.revrobotics.spark.SparkRelativeEncoder;
13+
import com.revrobotics.spark.SparkClosedLoopController;
14+
import com.revrobotics.spark.SparkFlex;
15+
import com.revrobotics.spark.SparkLowLevel.MotorType;
16+
import com.revrobotics.spark.SparkMax;
17+
import com.revrobotics.spark.SparkMaxAlternateEncoder;
2718
import com.revrobotics.spark.SparkSim;
28-
import com.revrobotics.spark.SparkLowLevel;
29-
19+
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
3020
import edu.wpi.first.hal.SimDevice;
3121
import edu.wpi.first.math.system.plant.DCMotor;
3222
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
23+
import org.carlmontrobotics.lib199.Lib199Subsystem;
24+
import org.carlmontrobotics.lib199.Mocks;
25+
import org.carlmontrobotics.lib199.REVLibErrorAnswer;
3326

3427
/**
3528
* An extension of {@link MockedMotorBase} which implements spark-max-specific functionality
@@ -52,10 +45,10 @@ public class MockSparkBase extends MockedMotorBase {
5245
private SparkAnalogSensorSim analogSensorImpl = null;
5346
private final String name;
5447

55-
public enum NEOType { //is it fine if we make it public so that MotorControllerFactory can access it?
48+
public enum NEOType {
5649
NEO(DCMotor.getNEO(1)),
5750
NEO550(DCMotor.getNeo550(1)),
58-
VORTEX(DCMotor.getNeoVortex(1)),
51+
VORTEX(DCMotor.getNeoVortex(1)),
5952
UNKNOWN(DCMotor.getNEO(1));
6053

6154
public DCMotor dcMotor;
@@ -110,7 +103,7 @@ public MockSparkBase(int port, MotorType type, String name, int countsPerRev, NE
110103
pidControllerImpl = new MockedSparkClosedLoopController(this);
111104
pidController = Mocks.createMock(SparkClosedLoopController.class, pidControllerImpl, new REVLibErrorAnswer());
112105
// pidController.feedbackSensor(encoder);
113-
106+
114107

115108
controllers.put(port, this);
116109

src/main/java/org/carlmontrobotics/lib199/sim/MockedCANCoder.java

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -4,13 +4,11 @@
44

55
import com.ctre.phoenix6.hardware.CANcoder;
66
import com.ctre.phoenix6.sim.CANcoderSimState;
7-
87
import edu.wpi.first.hal.HALValue;
9-
import edu.wpi.first.hal.SimBoolean;
108
import edu.wpi.first.hal.SimDevice;
119
import edu.wpi.first.hal.SimDevice.Direction;
12-
import edu.wpi.first.hal.simulation.SimValueCallback;
1310
import edu.wpi.first.hal.SimDouble;
11+
import edu.wpi.first.hal.simulation.SimValueCallback;
1412
import edu.wpi.first.wpilibj.simulation.SimDeviceSim;
1513

1614
public class MockedCANCoder {
@@ -37,4 +35,4 @@ public void callback(String name, int handle, int direction, HALValue value) {
3735
}, true);
3836
sims.put(port, this);
3937
}
40-
}
38+
}

src/main/java/org/carlmontrobotics/lib199/sim/MockedSparkClosedLoopController.java

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -13,9 +13,7 @@
1313
import com.revrobotics.spark.SparkMax;
1414
import com.revrobotics.spark.SparkMaxAlternateEncoder;
1515
import com.revrobotics.spark.SparkRelativeEncoder;
16-
import com.revrobotics.spark.config.ClosedLoopConfig;
1716
import com.revrobotics.spark.config.MAXMotionConfig;
18-
1917
import edu.wpi.first.math.MathUtil;
2018
import edu.wpi.first.math.controller.PIDController;
2119
import edu.wpi.first.math.controller.ProfiledPIDController;
@@ -60,7 +58,7 @@ public double getIAccum() {
6058
/**Get the MAXMotion internal setpoint position. */
6159
public double getMAXMotionSetpointPosition() {
6260
return setpoint;
63-
}
61+
}
6462

6563
/**Get the MAXMotion internal setpoint velocity. */
6664
public double getMAXMotionSetpointVelocity() {
@@ -76,16 +74,16 @@ public ClosedLoopSlot getSelectedSlot() {
7674
public double getSetpoint() {
7775
return setpoint;
7876
}
79-
77+
8078
/** Determine if the setpoint has been reached.*/
8179
public boolean isAtSetpoint() {return false;}
82-
80+
8381
/** Set the I accumulator of the closed loop controller. */
8482
public REVLibError setIAccum(double iAccum) {
8583
System.err.println("(MockedSparkMaxPIDController): setIAccum() is not currently implemented");
8684
return REVLibError.kNotImplemented;
8785
}
88-
/** Deprecated, for removal: This API element is subject to removal in a future version.
86+
/** Deprecated, for removal: This API element is subject to removal in a future version.
8987
* Use {@link #setSetpoint(double, SparkBase.ControlType)} instead
9088
*/
9189
@Deprecated
@@ -99,7 +97,7 @@ public REVLibError setReference(double value, SparkMax.ControlType ctrl) {
9997
public REVLibError setReference(double value, SparkMax.ControlType ctrl, ClosedLoopSlot pidSlot) {
10098
return setReference(value, ctrl, pidSlot, 0);
10199
}
102-
/** Deprecated, for removal: This API element is subject to removal in a future version.
100+
/** Deprecated, for removal: This API element is subject to removal in a future version.
103101
* Use {@link #setSetpoint(double, SparkBase.ControlType, ClosedLoopSlot, double)} instead*/
104102
@Deprecated
105103
public REVLibError setReference(double value, SparkMax.ControlType ctrl, ClosedLoopSlot pidSlot, double arbFeedforward) {

0 commit comments

Comments
 (0)