Skip to content

Commit 57a5d84

Browse files
fix sparkflex constructor
1 parent 7fc3dd2 commit 57a5d84

File tree

2 files changed

+40
-4
lines changed

2 files changed

+40
-4
lines changed

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

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,6 @@ public class MotorConfig {
1111
// See: https://www.chiefdelphi.com/t/rev-robotics-spark-flex-and-neo-vortex/442595/349?u=brettle
1212
// As a result I think 100C should be safe. I wouldn't increase it past 120. --Dean
1313
public static final MotorConfig NEO_VORTEX = new MotorConfig(100, 60);
14-
1514
public final int temperatureLimitCelsius, currentLimitAmps;
1615

1716
public MotorConfig(int temperatureLimitCelsius, int currentLimitAmps) {

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

Lines changed: 40 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -83,8 +83,8 @@ public static WPI_TalonSRX createTalon(int id) {
8383
return talon;
8484
}
8585

86-
/**
87-
* Create a sparkMax controller (NEO or 550) with defautl settings.
86+
/**
87+
* Create a default sparkMax controller (NEO or 550).
8888
*
8989
* @param id the port of the motor controller
9090
* @param motorConfig either MotorConfig.NEO or MotorConfig.NEO_550
@@ -114,7 +114,12 @@ else if (motorConfig==MotorConfig.NEO_VORTEX)
114114

115115
return spark;
116116
}
117-
117+
/**
118+
* Create a sparkMax controller (NEO or 550) with custom settings.
119+
*
120+
* @param id the port of the motor controller
121+
* @param config the custom config to set
122+
*/
118123
public static SparkMax createSparkMax(int id, SparkBaseConfig config) {
119124
SparkMax spark = null;
120125
if (RobotBase.isReal()) {
@@ -132,7 +137,38 @@ public static SparkMax createSparkMax(int id, SparkBaseConfig config) {
132137

133138
return spark;
134139
}
140+
/**
141+
* Create a default sparkFlex-Vortex controller.
142+
*
143+
* @param id the port of the motor controller
144+
*/
145+
public static SparkFlex createSparkFlex(int id) {
146+
MotorConfig motorConfig = MotorConfig.NEO_VORTEX;
135147

148+
SparkFlex spark=null;
149+
if (RobotBase.isReal()) {
150+
spark = new SparkFlex(id, SparkLowLevel.MotorType.kBrushless);
151+
} else {
152+
System.err.println("heyy... lib199 doesn't have sim support sorri");
153+
// spark = MockSparkMax.createMockSparkMax(id, SparkLowLevel.MotorType.kBrushless);
154+
}
155+
156+
// config.setPeriodicFramePeriod(SparkLowLevel.PeriodicFrame.kStatus0, 1);
157+
if (spark!=null)
158+
MotorErrors.reportSparkTemp(spark, motorConfig.temperatureLimitCelsius);
159+
160+
MotorErrors.checkSparkErrors(spark);
161+
162+
spark.configure(baseSparkFlexConfig(), SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters);
163+
164+
return spark;
165+
}
166+
/**
167+
* Create a sparkFlex controller (VORTEX) with custom settings.
168+
*
169+
* @param id the port of the motor controller
170+
* @param config the custom config to set
171+
*/
136172
public static SparkFlex createSparkFlex(int id, SparkBaseConfig config) {
137173
SparkFlex spark = null;
138174
if (RobotBase.isReal()) {
@@ -151,6 +187,7 @@ public static SparkFlex createSparkFlex(int id, SparkBaseConfig config) {
151187
return spark;
152188
}
153189

190+
154191
public static SparkBaseConfig baseSparkConfig() {
155192
SparkMaxConfig config = new SparkMaxConfig();
156193

0 commit comments

Comments
 (0)