Skip to content

Commit 72bdbc8

Browse files
committed
resolved most comments
1 parent 0e814d3 commit 72bdbc8

File tree

6 files changed

+25
-28
lines changed

6 files changed

+25
-28
lines changed

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

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
import com.ctre.phoenix6.hardware.CANcoder;
1414
import com.revrobotics.spark.SparkMax;
1515
import com.revrobotics.spark.SparkBase.PersistMode;
16+
import com.revrobotics.spark.SparkLowLevel.MotorType;
1617
import com.revrobotics.spark.config.SparkBaseConfig;
1718
import com.revrobotics.spark.config.SparkFlexConfig;
1819
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
@@ -24,11 +25,14 @@
2425
import com.revrobotics.spark.SparkLowLevel;
2526
import com.revrobotics.spark.SparkClosedLoopController;
2627

28+
import org.carlmontrobotics.lib199.sim.MockSparkFlex;
29+
import org.carlmontrobotics.lib199.sim.MockSparkMax;
2730
// import org.carlmontrobotics.lib199.sim.MockSparkFlex;
2831
// import org.carlmontrobotics.lib199.sim.MockSparkMax;
2932
import org.carlmontrobotics.lib199.sim.MockTalonSRX;
3033
import org.carlmontrobotics.lib199.sim.MockVictorSPX;
3134
import org.carlmontrobotics.lib199.sim.MockedCANCoder;
35+
import org.mockito.Mock;
3236

3337
import edu.wpi.first.cameraserver.CameraServer;
3438
import edu.wpi.first.cscore.UsbCamera;
@@ -125,8 +129,7 @@ public static SparkMax createSparkMax(int id, SparkBaseConfig config) {
125129
if (RobotBase.isReal()) {
126130
spark = new SparkMax(id, SparkLowLevel.MotorType.kBrushless);
127131
} else {
128-
System.err.println("heyy... lib199 doesn't have sim support sorri");
129-
// spark = MockSparkMax.createMockSparkMax(id, SparkLowLevel.MotorType.kBrushless);
132+
spark = MockSparkMax.createMockSparkMax(id, SparkLowLevel.MotorType.kBrushless, MockSparkMax.NEOType.NEO);
130133
}
131134
if (spark!=null)
132135
spark.configure(
@@ -150,7 +153,7 @@ public static SparkFlex createSparkFlex(int id) {
150153
spark = new SparkFlex(id, SparkLowLevel.MotorType.kBrushless);
151154
} else {
152155
System.err.println("heyy... lib199 doesn't have sim support sorri");
153-
// spark = MockSparkMax.createMockSparkMax(id, SparkLowLevel.MotorType.kBrushless);
156+
spark = MockSparkFlex.createMockSparkFlex(id, MotorType.kBrushless);
154157
}
155158

156159
// config.setPeriodicFramePeriod(SparkLowLevel.PeriodicFrame.kStatus0, 1);
@@ -193,7 +196,7 @@ public static SparkBaseConfig baseSparkConfig() {
193196

194197
config.idleMode(IdleMode.kBrake);
195198

196-
config.voltageCompensation(12);//FIXME does this need to be different for different motors?
199+
config.voltageCompensation(12);
197200
config.smartCurrentLimit(50);
198201

199202
config.closedLoop

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

Lines changed: 5 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,8 @@ public final class MotorErrors {
2727
private static final Map<SparkBase, Faults> stickyFlags = new ConcurrentSkipListMap<>(
2828
(spark1, spark2) -> (spark1.getDeviceId() - spark2.getDeviceId()));
2929

30+
private static final SparkBaseConfig OVERHEAT_CONFIG = new SparkMaxConfig().smartCurrentLimit(1);
31+
3032
public static final int kOverheatTripCount = 5;
3133

3234
static {
@@ -137,17 +139,12 @@ static void reportNextNSparkErrors(int n) {
137139
lastSparkErrorIndexReported = (lastSparkErrorIndexReported + n) % flags.size();
138140
}
139141

140-
//what does this even supposed to do??
141-
public static SparkMax createDummySparkMax() {
142-
return Mocks.mock(SparkMax.class, new REVLibErrorAnswer());
143-
}
144-
145142
@Deprecated
146143
public static void reportSparkMaxTemp(SparkMax spark, TemperatureLimit temperatureLimit) {
147144
reportSparkMaxTemp(spark, temperatureLimit.limit);
148145
}
149146

150-
public static boolean isSparkMaxOverheated(SparkMax spark){
147+
public static boolean isSparkOverheated(SparkBase spark){
151148
int id = spark.getDeviceId();
152149
int motorMaxTemp = sparkTemperatureLimits.get(id);
153150
return ( spark.getMotorTemperature() >= motorMaxTemp );
@@ -216,8 +213,8 @@ private static void reportSparkTemp(int port, SparkBase spark) {
216213
+ " degrees Celsius! It will be disabled until the robot code is restarted.");
217214
}
218215
spark.configure(
219-
new SparkMaxConfig().smartCurrentLimit(1),
220-
SparkBase.ResetMode.kResetSafeParameters,
216+
OVERHEAT_CONFIG,
217+
SparkBase.ResetMode.kNoResetSafeParameters,
221218
SparkBase.PersistMode.kNoPersistParameters);
222219
}
223220
}

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

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

3-
import com.revrobotics.spark.SparkMax;
3+
import com.revrobotics.spark.SparkBase;
44
import com.revrobotics.spark.config.ClosedLoopConfig;
55
import com.revrobotics.spark.config.SparkBaseConfig;
66
import com.revrobotics.spark.config.SparkMaxConfig;
@@ -20,14 +20,14 @@
2020
public class SparkVelocityPIDController implements Sendable {
2121

2222
@SuppressWarnings("unused")
23-
private final SparkMax spark;
23+
private final SparkBase spark;
2424
private final SparkClosedLoopController pidController;
2525
private final RelativeEncoder encoder;
2626
private final String name;
2727
private double targetSpeed, tolerance;
2828
private double currentP, currentI, currentD, kS, kV;
2929

30-
public SparkVelocityPIDController(String name, SparkMax spark, double defaultP, double defaultI, double defaultD, double kS, double kV, double targetSpeed, double tolerance) {
30+
public SparkVelocityPIDController(String name, SparkBase spark, double defaultP, double defaultI, double defaultD, double kS, double kV, double targetSpeed, double tolerance) {
3131
this.spark = spark;
3232
this.pidController = spark.getClosedLoopController();
3333
this.encoder = spark.getEncoder();

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

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -52,10 +52,10 @@ public class MockSparkBase extends MockedMotorBase {
5252
private SparkAnalogSensorSim analogSensorImpl = null;
5353
private final String name;
5454

55-
enum NEOType {
55+
public enum NEOType { //is it fine if we make it public so that MotorControllerFactory can access it?
5656
NEO(DCMotor.getNEO(1)),
5757
NEO550(DCMotor.getNeo550(1)),
58-
Vortex(DCMotor.getNeoVortex(1)),
58+
VORTEX(DCMotor.getNeoVortex(1)),
5959
UNKNOWN(DCMotor.getNEO(1));
6060

6161
public DCMotor dcMotor;
@@ -73,20 +73,21 @@ private NEOType(DCMotor dcmotordata){
7373
* to follow the inversion state of the motor and its {@code setInverted} method will be disabled.
7474
* @param name the name of the type of controller ("SparkMax" or "SparkFlex")
7575
* @param countsPerRev the number of counts per revolution of this controller's built-in encoder.
76+
* @param neoType the type of NEO motor
7677
*/
7778
public MockSparkBase(int port, MotorType type, String name, int countsPerRev, NEOType neoType) {
7879
super(name, port);
7980
this.type = type;
8081
this.name = name;
8182

82-
if (neoType != NEOType.Vortex){ //WARNING can't initialize a sparkbase without an actual spark...
83-
this.motor = new SparkMax(port,type);
83+
if (neoType == NEOType.VORTEX){ //only vortex uses sparkflex
84+
this.motor = new SparkFlex(port,type);
8485
this.spark = new SparkSim(
8586
this.motor,
8687
neoType.dcMotor
8788
);
88-
} else { //only vortex uses sparkflex
89-
this.motor = new SparkFlex(port,type);
89+
} else { //WARNING can't initialize a sparkbase without an actual spark...
90+
this.motor = new SparkMax(port,type);
9091
this.spark = new SparkSim(
9192
this.motor,
9293
neoType.dcMotor
@@ -229,7 +230,6 @@ public void close() {
229230
if (encoder != null) {
230231
encoder.close();
231232
}
232-
//simply drop all references for garbage collection (?)
233233
absoluteEncoderImpl=null;
234234
analogSensorImpl=null;
235235
alternateEncoder=null;

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
public class MockSparkFlex extends MockSparkBase {
1010

1111
public MockSparkFlex(int port, MotorType type) {
12-
super(port, type, "CANSparkFlex", 7168, NEOType.Vortex);
12+
super(port, type, "CANSparkFlex", 7168, NEOType.VORTEX);
1313
}
1414

1515
public static SparkFlex createMockSparkFlex(int portPWM, MotorType type) {

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

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,6 @@
88

99
import org.mockito.internal.reporting.SmartPrinter;
1010

11-
// import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue;
1211
import com.ctre.phoenix6.configs.CANcoderConfiguration;
1312
import com.ctre.phoenix6.hardware.CANcoder;
1413
import com.revrobotics.spark.SparkMax;
@@ -81,7 +80,7 @@ public SwerveModule(SwerveConfig config, ModuleType type, SparkMax drive, SparkM
8180
turnConfig.inverted(config.turnInversion[arrIndex]);
8281

8382
double drivePositionFactor = config.wheelDiameterMeters * Math.PI / config.driveGearing;
84-
final double driveVelocityFactor = drivePositionFactor / 60;//why by 60?
83+
final double driveVelocityFactor = drivePositionFactor / 60;
8584
driveConfig.encoder
8685
.positionConversionFactor(drivePositionFactor)
8786
.velocityConversionFactor(driveVelocityFactor);
@@ -200,9 +199,7 @@ public void drivePeriodic() {
200199
.calculateWithVelocities(
201200
actualSpeed,
202201
desiredSpeed + extraAccel * TimedRobot.kDefaultPeriod//m/s + ( m/s^2 * s )
203-
);//clippedAcceleration);
204-
//calculateAntiGravitationalA(pitchDegSupplier.get(), rollDegSupplier.get())
205-
202+
);//clippedAcceleration);
206203
// Use robot characterization as a simple physical model to account for internal resistance, frcition, etc.
207204
// Add a PID adjustment for error correction (also "drives" the actual speed to the desired speed)
208205
double pidVolts = drivePIDController.calculate(actualSpeed, desiredSpeed);

0 commit comments

Comments
 (0)