Skip to content

Commit a55996f

Browse files
Merge pull request #33 from DeepBlueRobotics/motor-temp
Lower SparkMax Current Limits
2 parents a219901 + ed268f4 commit a55996f

3 files changed

Lines changed: 54 additions & 2 deletions

File tree

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
package org.carlmontrobotics;
2+
3+
public class MotorConfig {
4+
5+
public static final MotorConfig NEO = new MotorConfig(70, 40);
6+
public static final MotorConfig NEO_550 = new MotorConfig(40, 20);
7+
8+
public final int temperatureLimit, currentLimit;
9+
10+
public MotorConfig(int temperatureLimit, int currentLimit) {
11+
this.temperatureLimit = temperatureLimit;
12+
this.currentLimit = currentLimit;
13+
}
14+
15+
}

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

Lines changed: 37 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717
import com.revrobotics.CANSparkMaxLowLevel;
1818
import com.revrobotics.SparkMaxPIDController;
1919

20-
import org.carlmontrobotics.lib199.MotorErrors.TemperatureLimit;
20+
import org.carlmontrobotics.MotorConfig;
2121
import org.carlmontrobotics.lib199.sim.MockSparkMax;
2222
import org.carlmontrobotics.lib199.sim.MockTalonSRX;
2323
import org.carlmontrobotics.lib199.sim.MockVictorSPX;
@@ -78,10 +78,12 @@ public static WPI_TalonSRX createTalon(int id) {
7878

7979
//checks for spark max errors
8080

81-
public static CANSparkMax createSparkMax(int id, TemperatureLimit temperatureLimit) {
81+
@Deprecated
82+
public static CANSparkMax createSparkMax(int id, MotorErrors.TemperatureLimit temperatureLimit) {
8283
return createSparkMax(id, temperatureLimit.limit);
8384
}
8485

86+
@Deprecated
8587
public static CANSparkMax createSparkMax(int id, int temperatureLimit) {
8688
CANSparkMax spark;
8789
if (RobotBase.isReal()) {
@@ -115,6 +117,39 @@ public static CANSparkMax createSparkMax(int id, int temperatureLimit) {
115117
return spark;
116118
}
117119

120+
public static CANSparkMax createSparkMax(int id, MotorConfig config) {
121+
CANSparkMax spark;
122+
if (RobotBase.isReal()) {
123+
spark = new CachedSparkMax(id, CANSparkMaxLowLevel.MotorType.kBrushless);
124+
if (spark.getFirmwareVersion() == 0) {
125+
spark.close();
126+
System.err.println("SparkMax on port: " + id + " is not connected!");
127+
return MotorErrors.createDummySparkMax();
128+
}
129+
} else {
130+
spark = MockSparkMax.createMockSparkMax(id, CANSparkMaxLowLevel.MotorType.kBrushless);
131+
}
132+
133+
MotorErrors.reportSparkMaxTemp(spark, config.temperatureLimit);
134+
135+
MotorErrors.reportError(spark.restoreFactoryDefaults());
136+
MotorErrors.reportError(spark.follow(ExternalFollower.kFollowerDisabled, 0));
137+
MotorErrors.reportError(spark.setIdleMode(IdleMode.kBrake));
138+
MotorErrors.reportError(spark.enableVoltageCompensation(12));
139+
MotorErrors.reportError(spark.setSmartCurrentLimit(config.currentLimit));
140+
141+
MotorErrors.checkSparkMaxErrors(spark);
142+
143+
SparkMaxPIDController controller = spark.getPIDController();
144+
MotorErrors.reportError(controller.setOutputRange(-1, 1));
145+
MotorErrors.reportError(controller.setP(0));
146+
MotorErrors.reportError(controller.setI(0));
147+
MotorErrors.reportError(controller.setD(0));
148+
MotorErrors.reportError(controller.setFF(0));
149+
150+
return spark;
151+
}
152+
118153
public static CANCoder createCANCoder(int port) {
119154
CANCoder canCoder = new CANCoder(port);
120155
if(RobotBase.isSimulation()) new MockedCANCoder(canCoder);

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

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -99,6 +99,7 @@ public static CANSparkMax createDummySparkMax() {
9999
return DummySparkMaxAnswer.DUMMY_SPARK_MAX;
100100
}
101101

102+
@Deprecated
102103
public static void reportSparkMaxTemp(CANSparkMax spark, TemperatureLimit temperatureLimit) {
103104
reportSparkMaxTemp(spark, temperatureLimit.limit);
104105
}
@@ -126,6 +127,7 @@ public static void doReportSparkMaxTemp() {
126127

127128
private MotorErrors() {}
128129

130+
@Deprecated
129131
public static enum TemperatureLimit {
130132
NEO(70), NEO_550(40);
131133

0 commit comments

Comments
 (0)