Skip to content

Commit b4d6e0b

Browse files
committed
resolved more comments
1 parent c24939a commit b4d6e0b

File tree

6 files changed

+46
-87
lines changed

6 files changed

+46
-87
lines changed

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

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

33
public class MotorConfig {
44

5-
public static final MotorConfig NEO = new MotorConfig(70, 40);
6-
public static final MotorConfig NEO_550 = new MotorConfig(40, 20);
5+
public static final MotorConfig NEO = new MotorConfig(70, 40, MotorControllerType.SPARK_MAX);
6+
public static final MotorConfig NEO_550 = new MotorConfig(70, 40, MotorControllerType.SPARK_MAX);
7+
public static final MotorConfig NEO_2 = new MotorConfig(70, 40, MotorControllerType.SPARK_MAX); //TODO: find the max temp for NEO 2.0
78

89
// The temp limit of 100C for the Vortex is based on the fact that its temp sensors are mounted directly on the
910
// windings (which is not the case for the Neo or Neo550, causing them to have very delayed temp readings) and the
1011
// fact that the winding enamel will melt at 140C.
1112
// See: https://www.chiefdelphi.com/t/rev-robotics-spark-flex-and-neo-vortex/442595/349?u=brettle
1213
// As a result I think 100C should be safe. I wouldn't increase it past 120. --Dean
13-
public static final MotorConfig NEO_VORTEX = new MotorConfig(100, 60);
14+
public static final MotorConfig NEO_VORTEX = new MotorConfig(100, 40, MotorControllerType.SPARK_FLEX);
15+
public static final MotorConfig NEO_SOLO_VORTEX = new MotorConfig(100, 40, MotorControllerType.SPARK_MAX);
1416
public final int temperatureLimitCelsius, currentLimitAmps;
17+
public final MotorControllerType controllerType;
1518

16-
public MotorConfig(int temperatureLimitCelsius, int currentLimitAmps) {
19+
public MotorConfig(int temperatureLimitCelsius, int currentLimitAmps, MotorControllerType controllerType) {
1720
this.temperatureLimitCelsius = temperatureLimitCelsius;
1821
this.currentLimitAmps = currentLimitAmps;
22+
this.controllerType = controllerType;
1923
}
2024

25+
public MotorControllerType getControllerType() {
26+
return controllerType;
27+
}
2128
}

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

Lines changed: 12 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -99,19 +99,15 @@ public static WPI_TalonSRX createTalon(int id) {
9999
* @param motorConfig either MotorConfig.NEO or MotorConfig.NEO_550
100100
*/
101101
public static SparkMax createSparkMax(int id, MotorConfig motorConfig) {
102-
if (motorConfig.temperatureLimitCelsius == MotorConfig.NEO.temperatureLimitCelsius) {
103-
return createSparkMax(id, sparkConfig(SparkMotorType.NEO));
104-
}else{
105-
return createSparkMax(id, sparkConfig(SparkMotorType.NEO550));
106-
}
102+
return createSparkMax(id, motorConfig, sparkConfig(motorConfig));
107103
}
108104
/**
109105
* Create a sparkMax controller (NEO or 550) with custom settings.
110106
*
111107
* @param id the port of the motor controller
112108
* @param config the custom config to set
113109
*/
114-
public static SparkMax createSparkMax(int id, SparkBaseConfig config) {
110+
public static SparkMax createSparkMax(int id, MotorConfig motorConfig, SparkBaseConfig config) {
115111
SparkMax spark;
116112
if (RobotBase.isReal()) {
117113
spark = new SparkMax(id, SparkLowLevel.MotorType.kBrushless);
@@ -123,6 +119,8 @@ public static SparkMax createSparkMax(int id, SparkBaseConfig config) {
123119
SparkBase.ResetMode.kResetSafeParameters,
124120
SparkBase.PersistMode.kNoPersistParameters
125121
);
122+
MotorErrors.reportSparkTemp(spark, motorConfig.temperatureLimitCelsius);
123+
MotorErrors.checkSparkErrors(spark);
126124

127125
return spark;
128126
}
@@ -132,15 +130,15 @@ public static SparkMax createSparkMax(int id, SparkBaseConfig config) {
132130
* @param id the port of the motor controller
133131
*/
134132
public static SparkFlex createSparkFlex(int id) {
135-
return createSparkFlex(id, sparkConfig(SparkMotorType.VORTEX));
133+
return createSparkFlex(id, MotorConfig.NEO_VORTEX, sparkConfig(MotorConfig.NEO_VORTEX));
136134
}
137135
/**
138136
* Create a sparkFlex controller (VORTEX) with custom settings.
139137
*
140138
* @param id the port of the motor controller
141139
* @param config the custom config to set
142140
*/
143-
public static SparkFlex createSparkFlex(int id, SparkBaseConfig config) {
141+
public static SparkFlex createSparkFlex(int id, MotorConfig motorConfig, SparkBaseConfig config) {
144142
SparkFlex spark = null;
145143
if (RobotBase.isReal()) {
146144
spark = new SparkFlex(id, SparkLowLevel.MotorType.kBrushless);
@@ -154,6 +152,9 @@ public static SparkFlex createSparkFlex(int id, SparkBaseConfig config) {
154152
SparkBase.PersistMode.kPersistParameters
155153
);
156154

155+
MotorErrors.reportSparkTemp(spark, motorConfig.temperatureLimitCelsius);
156+
MotorErrors.checkSparkErrors(spark);
157+
157158
return spark;
158159
}
159160

@@ -179,9 +180,9 @@ public static MotorControllerType getControllerType(SparkBase motor){
179180
return null;
180181
}
181182

182-
public static SparkBaseConfig sparkConfig(SparkMotorType motor){
183+
public static SparkBaseConfig sparkConfig(MotorConfig motorConfig){
183184
SparkBaseConfig config = null;
184-
switch(motor.getControllerType()){
185+
switch(motorConfig.getControllerType()){
185186
case SPARK_MAX:
186187
config = new SparkMaxConfig();
187188
break;
@@ -192,28 +193,14 @@ public static SparkBaseConfig sparkConfig(SparkMotorType motor){
192193
//configs that apply to all motors
193194
config.idleMode(IdleMode.kBrake);
194195
config.voltageCompensation(12);
195-
config.smartCurrentLimit(40); //40 amps is the fuse rating for fuses for each individual motor on the PDP
196+
config.smartCurrentLimit(motorConfig.currentLimitAmps);
196197

197198
config.closedLoop
198199
.minOutput(-1)
199200
.maxOutput(1)
200201
.pid(0,0,0)
201202
.velocityFF(0);
202203

203-
204-
//motor specific configs
205-
switch(motor){
206-
case NEO:
207-
break;
208-
case NEO550:
209-
config.smartCurrentLimit(20); //so motor no go smoky
210-
break;
211-
case VORTEX, SOLO_VORTEX: // the config for a vortex should be the same if it uses a spark max with a solo adapter or a spark flex, so I just combined them together
212-
break;
213-
case NEO_2:
214-
break;
215-
}
216-
217204
return config;
218205
}
219206
}
Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,15 @@
11
package org.carlmontrobotics.lib199;
22

3+
import com.revrobotics.spark.SparkBase;
4+
import com.revrobotics.spark.config.SparkBaseConfig;
5+
36
public enum MotorControllerType {
47
SPARK_MAX,
5-
SPARK_FLEX
8+
SPARK_FLEX;
9+
public static MotorControllerType getMotorControllerType(SparkBase motor){
10+
return MotorControllerFactory.getControllerType(motor);
11+
}
12+
public SparkBaseConfig createConfig(){
13+
return MotorControllerFactory.createConfig(this);
14+
}
615
}

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

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,8 @@ public static void checkSparkErrors(SparkBase spark) {
9090
System.err.println("Sticky Faults! (spark id " + spark.getDeviceId() + "): [" + formatStickyFaults(spark) + "], Ouch!");
9191
}
9292
spark.clearFaults();
93+
flags.put(spark, faults);
94+
stickyFlags.put(spark, stickyFaults);
9395
}
9496

9597
private static String formatFaults(Faults f) {

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

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

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

Lines changed: 11 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,6 @@
77
import java.util.function.Supplier;
88

99
import org.carlmontrobotics.lib199.MotorControllerType;
10-
import org.carlmontrobotics.lib199.SparkMotorType;
1110
import org.mockito.internal.reporting.SmartPrinter;
1211

1312
import com.ctre.phoenix6.configs.CANcoderConfiguration;
@@ -77,26 +76,12 @@ public enum ModuleType {FL, FR, BL, BR};
7776
MotorControllerType driveMotorType;
7877
MotorControllerType turnMotorType;
7978

80-
public SwerveModule(SwerveConfig config, ModuleType type, SparkBase drive, SparkBase turn, MotorControllerType driveMotorType, MotorControllerType turnMotorType, CANcoder turnEncoder,
79+
public SwerveModule(SwerveConfig config, ModuleType type, SparkBase drive, SparkBase turn, CANcoder turnEncoder,
8180
int arrIndex, Supplier<Float> pitchDegSupplier, Supplier<Float> rollDegSupplier) {
82-
this.driveMotorType = driveMotorType;
83-
this.turnMotorType = turnMotorType;
84-
switch(driveMotorType) {
85-
case SPARK_MAX:
86-
driveConfig = new SparkMaxConfig();
87-
break;
88-
case SPARK_FLEX:
89-
driveConfig = new SparkFlexConfig();
90-
break;
91-
}
92-
switch(turnMotorType) {
93-
case SPARK_MAX:
94-
turnConfig = new SparkMaxConfig();
95-
break;
96-
case SPARK_FLEX:
97-
turnConfig = new SparkFlexConfig();
98-
break;
99-
}
81+
driveMotorType = MotorControllerType.getMotorControllerType(drive);
82+
turnMotorType = MotorControllerType.getMotorControllerType(turn);
83+
driveConfig = driveMotorType.createConfig();
84+
turnConfig = turnMotorType.createConfig();
10085
//SmartDashboard.putNumber("Target Angle (deg)", 0.0);
10186
String moduleString = type.toString();
10287
this.timer = new Timer();
@@ -466,31 +451,19 @@ public void toggleMode() {
466451
public void brake() {
467452
idleMode = IdleMode.kBrake;
468453
SparkBaseConfig config = null;
469-
switch(driveMotorType){
470-
case SPARK_MAX:
471-
config = new SparkMaxConfig().idleMode(IdleMode.kBrake);
472-
break;
473-
case SPARK_FLEX:
474-
config = new SparkFlexConfig().idleMode(IdleMode.kBrake);
475-
break;
476-
}
454+
config = driveMotorType.createConfig().idleMode(idleMode);
477455
drive.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
478-
turn .configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
456+
config = turnMotorType.createConfig().idleMode(idleMode);
457+
turn.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
479458
}
480459

481460
public void coast() {
482461
idleMode = IdleMode.kCoast;
483462
SparkBaseConfig config = null;
484-
switch(driveMotorType){
485-
case SPARK_MAX:
486-
config = new SparkMaxConfig().idleMode(IdleMode.kCoast);
487-
break;
488-
case SPARK_FLEX:
489-
config = new SparkFlexConfig().idleMode(IdleMode.kCoast);
490-
break;
491-
}
463+
config = driveMotorType.createConfig().idleMode(idleMode);
492464
drive.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
493-
turn .configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
465+
config = turnMotorType.createConfig().idleMode(idleMode);
466+
turn.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
494467
}
495468

496469
/**

0 commit comments

Comments
 (0)