Skip to content

Commit bc7f07d

Browse files
committed
resolved some comments
1 parent c3bc942 commit bc7f07d

File tree

6 files changed

+45
-129
lines changed

6 files changed

+45
-129
lines changed

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

Lines changed: 10 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -124,39 +124,37 @@ else if (motorConfig==MotorConfig.NEO_VORTEX)
124124
* @param config the custom config to set
125125
*/
126126
public static SparkMax createSparkMax(int id, SparkBaseConfig config) {
127-
SparkMax spark = null;
127+
SparkMax spark;
128128
if (RobotBase.isReal()) {
129129
spark = new SparkMax(id, SparkLowLevel.MotorType.kBrushless);
130130
} else {
131131
spark = MockSparkMax.createMockSparkMax(id, SparkLowLevel.MotorType.kBrushless, MockSparkMax.NEOType.NEO); //what if the Mocked motor is a 550 with a custom config?
132132
}
133-
if (spark!=null)
134-
spark.configure(
135-
config,
136-
SparkBase.ResetMode.kResetSafeParameters,
137-
SparkBase.PersistMode.kNoPersistParameters
138-
);
133+
spark.configure(
134+
config,
135+
SparkBase.ResetMode.kResetSafeParameters,
136+
SparkBase.PersistMode.kNoPersistParameters
137+
);
139138

140139
return spark;
141140
}
142141
/**
143-
* Create a default sparkFlex-Vortex controller.
142+
* Create a default SparkFlex-Vortex controller.
144143
*
145144
* @param id the port of the motor controller
146145
*/
147146
public static SparkFlex createSparkFlex(int id) {
148147
MotorConfig motorConfig = MotorConfig.NEO_VORTEX;
149148

150-
SparkFlex spark=null;
149+
SparkFlex spark;
151150
if (RobotBase.isReal()) {
152151
spark = new SparkFlex(id, SparkLowLevel.MotorType.kBrushless);
153152
} else {
154153
spark = MockSparkFlex.createMockSparkFlex(id, MotorType.kBrushless);
155154
}
156155

157156
// config.setPeriodicFramePeriod(SparkLowLevel.PeriodicFrame.kStatus0, 1);
158-
if (spark!=null)
159-
MotorErrors.reportSparkTemp(spark, motorConfig.temperatureLimitCelsius);
157+
MotorErrors.reportSparkTemp(spark, motorConfig.temperatureLimitCelsius);
160158

161159
MotorErrors.checkSparkErrors(spark);
162160

@@ -181,7 +179,7 @@ public static SparkFlex createSparkFlex(int id, SparkFlexConfig config) {
181179
spark.configure(
182180
config,
183181
SparkBase.ResetMode.kResetSafeParameters,
184-
SparkBase.PersistMode.kNoPersistParameters
182+
SparkBase.PersistMode.kPersistParameters
185183
);
186184

187185
return spark;

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

Lines changed: 26 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
import com.revrobotics.spark.SparkMax;
1313
import com.revrobotics.spark.SparkBase.Faults;
1414
import com.revrobotics.spark.config.SparkBaseConfig;
15+
import com.revrobotics.spark.config.SparkFlexConfig;
1516
import com.revrobotics.spark.config.SparkMaxConfig;
1617
import com.revrobotics.REVLibError;
1718

@@ -27,7 +28,9 @@ public final class MotorErrors {
2728
private static final Map<SparkBase, Faults> stickyFlags = new ConcurrentSkipListMap<>(
2829
(spark1, spark2) -> (spark1.getDeviceId() - spark2.getDeviceId()));
2930

30-
private static final SparkBaseConfig OVERHEAT_CONFIG = new SparkMaxConfig().smartCurrentLimit(1);
31+
private static final SparkBaseConfig OVERHEAT_MAX_CONFIG = new SparkMaxConfig().smartCurrentLimit(1);
32+
private static final SparkBaseConfig OVERHEAT_FLEX_CONFIG = new SparkFlexConfig().smartCurrentLimit(1);
33+
3134

3235
public static final int kOverheatTripCount = 5;
3336

@@ -75,8 +78,8 @@ public static void checkSparkErrors(SparkBase spark) {
7578
// short faults = spark.getFaults();
7679
Faults faults = spark.getFaults();
7780
Faults stickyFaults = spark.getStickyFaults();
78-
Faults prevFaults = flags.containsKey(spark) ? flags.get(spark) : null;
79-
Faults prevStickyFaults = stickyFlags.containsKey(spark) ? stickyFlags.get(spark) : null;
81+
Faults prevFaults = flags.getOrDefault(spark, null);
82+
Faults prevStickyFaults = stickyFlags.getOrDefault(spark, null);
8083

8184
if (spark.hasActiveFault() && prevFaults!=null && prevFaults.rawBits != faults.rawBits) {
8285
System.err.println("Fault Errors! (spark id " + spark.getDeviceId() + "): [" + formatFaults(spark) + "], ooF!");
@@ -85,17 +88,9 @@ public static void checkSparkErrors(SparkBase spark) {
8588
System.err.println("Sticky Faults! (spark id " + spark.getDeviceId() + "): [" + formatStickyFaults(spark) + "], Ouch!");
8689
}
8790
spark.clearFaults();
88-
flags.put(spark, faults);
89-
stickyFlags.put(spark, stickyFaults);
90-
}
91-
92-
@Deprecated
93-
public static void checkSparkMaxErrors(SparkMax spark) {
94-
checkSparkErrors((SparkBase)spark);
9591
}
9692

97-
private static String formatFaults(SparkBase spark) {
98-
Faults f = spark.getFaults();
93+
private static String formatFaults(Faults f) {
9994
return "" //i hope this makes you proud of yourself, REVLib
10095
+ (f.can ? "CAN " : "")
10196
+ (f.escEeprom ? "Flash ROM " : "")
@@ -108,18 +103,14 @@ private static String formatFaults(SparkBase spark) {
108103
;
109104
}
110105

106+
private static String formatFaults(SparkBase spark) {
107+
Faults f = spark.getFaults();
108+
return formatFaults(f);
109+
}
110+
111111
private static String formatStickyFaults(SparkBase spark) {
112112
Faults f = spark.getStickyFaults();
113-
return ""
114-
+ (f.can ? "CAN " : "")
115-
+ (f.escEeprom ? "Flash ROM " : "")
116-
+ (f.firmware ? "Firmware " : "")
117-
+ (f.gateDriver ? "Gate Driver " : "")
118-
+ (f.motorType ? "Motor Type " : "")
119-
+ (f.other ? "Other " : "")
120-
+ (f.sensor ? "Sensor " : "")
121-
+ (f.temperature ? "Temperature " : "")
122-
;
113+
return formatFaults(f);
123114
}
124115

125116
@Deprecated
@@ -139,22 +130,12 @@ static void reportNextNSparkErrors(int n) {
139130
lastSparkErrorIndexReported = (lastSparkErrorIndexReported + n) % flags.size();
140131
}
141132

142-
@Deprecated
143-
public static void reportSparkMaxTemp(SparkMax spark, TemperatureLimit temperatureLimit) {
144-
reportSparkMaxTemp(spark, temperatureLimit.limit);
145-
}
146-
147133
public static boolean isSparkOverheated(SparkBase spark){
148134
int id = spark.getDeviceId();
149135
int motorMaxTemp = sparkTemperatureLimits.get(id);
150136
return ( spark.getMotorTemperature() >= motorMaxTemp );
151137
}
152138

153-
@Deprecated
154-
public static void reportSparkMaxTemp(SparkMax spark, int temperatureLimit) {
155-
reportSparkTemp((SparkBase) spark, temperatureLimit);
156-
}
157-
158139
public static void reportSparkTemp(SparkBase spark, int temperatureLimit) {
159140
int id = spark.getDeviceId();
160141
temperatureSparks.put(id, spark);
@@ -212,10 +193,19 @@ private static void reportSparkTemp(int port, SparkBase spark) {
212193
System.err.println("Port " + port + " spark is operating at " + temp
213194
+ " degrees Celsius! It will be disabled until the robot code is restarted.");
214195
}
215-
spark.configure(
216-
OVERHEAT_CONFIG,
217-
SparkBase.ResetMode.kNoResetSafeParameters,
218-
SparkBase.PersistMode.kNoPersistParameters);
196+
if (spark.getClass() == SparkMax.class) {
197+
spark.configure(
198+
OVERHEAT_MAX_CONFIG,
199+
SparkBase.ResetMode.kNoResetSafeParameters,
200+
SparkBase.PersistMode.kNoPersistParameters);
201+
} else if (spark.getClass() == SparkFlex.class) {
202+
spark.configure(
203+
OVERHEAT_FLEX_CONFIG,
204+
SparkBase.ResetMode.kNoResetSafeParameters,
205+
SparkBase.PersistMode.kNoPersistParameters);
206+
}else{
207+
System.err.println("Unknown spark :(");
208+
}
219209
}
220210
}
221211

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

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@
44
import com.revrobotics.spark.config.ClosedLoopConfig;
55
import com.revrobotics.spark.config.SparkBaseConfig;
66
import com.revrobotics.spark.config.SparkMaxConfig;
7-
// import com.revrobotics.SparkBase.ControlType;
87
import com.revrobotics.RelativeEncoder;
98
import com.revrobotics.spark.ClosedLoopSlot;
109
import com.revrobotics.spark.SparkBase;

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

Lines changed: 9 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,8 @@
2626
import edu.wpi.first.math.kinematics.SwerveModuleState;
2727
import edu.wpi.first.math.trajectory.TrapezoidProfile;
2828
import edu.wpi.first.math.util.Units;
29-
import edu.wpi.first.units.measure.Mass;
3029
import edu.wpi.first.units.Measure;
30+
import edu.wpi.first.units.measure.Mass;
3131
import edu.wpi.first.util.sendable.Sendable;
3232
import edu.wpi.first.util.sendable.SendableBuilder;
3333
import edu.wpi.first.util.sendable.SendableRegistry;
@@ -66,8 +66,7 @@ public enum ModuleType {FL, FR, BL, BR};
6666
private double maxTurnVelocityWithoutTippingRps;
6767

6868
// Store encoder and config values since configAccessor is not available in new REV API
69-
private IdleMode driveIdleMode = IdleMode.kBrake;
70-
private IdleMode turnIdleMode = IdleMode.kBrake;
69+
private IdleMode idleMode = IdleMode.kBrake;
7170
private static final int NEO_HALL_COUNTS_PER_REV = 42;
7271
private static final int ENCODER_POSITION_PERIOD_MS = 20;
7372
private int encoderAverageDepth = 2;
@@ -197,7 +196,7 @@ public ModuleType getType() {
197196
private double prevTurnVelocity = 0;
198197
public void periodic() {
199198
drivePeriodic();
200-
updateSmartDashboard();
199+
// updateSmartDashboard();
201200
turnPeriodic();
202201
}
203202

@@ -208,8 +207,8 @@ public void drivePeriodic() {
208207
double targetVoltage = (actualSpeed >= 0 ? forwardSimpleMotorFF : backwardSimpleMotorFF)
209208
.calculateWithVelocities(
210209
actualSpeed,
211-
desiredSpeed + extraAccel * TimedRobot.kDefaultPeriod//m/s + ( m/s^2 * s )
212-
);//clippedAcceleration);
210+
desiredSpeed + extraAccel * TimedRobot.kDefaultPeriod //m/s + ( m/s^2 * s )
211+
);
213212
// Use robot characterization as a simple physical model to account for internal resistance, frcition, etc.
214213
// Add a PID adjustment for error correction (also "drives" the actual speed to the desired speed)
215214
double pidVolts = drivePIDController.calculate(actualSpeed, desiredSpeed);
@@ -436,21 +435,20 @@ public void updateSmartDashboard() {
436435
}
437436

438437
public void toggleMode() {
439-
if (driveIdleMode == IdleMode.kBrake && turnIdleMode == IdleMode.kCoast) coast();
438+
if (idleMode == IdleMode.kBrake && idleMode == IdleMode.kCoast) coast();
440439
else brake();
441440
}
442441

443442
public void brake() {
444-
driveIdleMode = IdleMode.kBrake;
445-
turnIdleMode = IdleMode.kBrake;
443+
idleMode = IdleMode.kBrake;
446444
SparkBaseConfig config = new SparkMaxConfig().idleMode(IdleMode.kBrake);
447445
drive.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
448446
turn .configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
449447
}
450448

451449
public void coast() {
452-
driveIdleMode = IdleMode.kCoast;
453-
turnIdleMode = IdleMode.kCoast;
450+
idleMode = IdleMode.kCoast;
451+
idleMode = IdleMode.kCoast;
454452
SparkBaseConfig config = new SparkMaxConfig().idleMode(IdleMode.kCoast);
455453
drive.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
456454
turn .configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);

src/test/java/org/carlmontrobotics/lib199/DummySparkMaxAnswerTest.txt

Lines changed: 0 additions & 61 deletions
This file was deleted.

src/test/java/org/carlmontrobotics/lib199/MotorErrorsTest.java

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,6 @@
1010

1111
import com.ctre.phoenix.ErrorCode;
1212
import com.revrobotics.REVLibError;
13-
// import com.revrobotics.SparkMax;
14-
//import com.revrobotics.spark.SparkBase.Faults;
1513

1614
import com.revrobotics.spark.SparkMax;
1715

@@ -166,12 +164,6 @@ public void testStickyFaultReporting() {
166164
assertEquals(0, errStream.toByteArray().length);
167165
}
168166

169-
//FIXME: do we need this?
170-
// @Test
171-
// public void testDummySparkMax() {
172-
// DummySparkMaxAnswerTest.assertTestResponses(MotorErrors.createDummySparkMax());
173-
// }
174-
175167
@Test
176168
public void testReportSparkMaxTemp() {
177169
assertTrue(MotorErrors.kOverheatTripCount > 0);

0 commit comments

Comments
 (0)