|
6 | 6 |
|
7 | 7 | import java.util.function.Supplier; |
8 | 8 |
|
| 9 | +import org.carlmontrobotics.lib199.MotorControllerFactory; |
9 | 10 | import org.carlmontrobotics.lib199.MotorControllerType; |
10 | 11 | import org.mockito.internal.reporting.SmartPrinter; |
11 | 12 |
|
|
18 | 19 | import com.revrobotics.spark.SparkMax; |
19 | 20 | import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; |
20 | 21 | import com.revrobotics.spark.config.SparkBaseConfig; |
| 22 | +import com.revrobotics.spark.config.SparkBaseConfigAccessor; |
21 | 23 | import com.revrobotics.spark.config.SparkMaxConfig; |
22 | 24 | import com.revrobotics.spark.config.SparkFlexConfig; |
23 | 25 |
|
@@ -71,13 +73,18 @@ public enum ModuleType {FL, FR, BL, BR}; |
71 | 73 |
|
72 | 74 | MotorControllerType driveMotorType; |
73 | 75 | MotorControllerType turnMotorType; |
| 76 | + |
| 77 | + SparkBaseConfigAccessor driveConfigAccessor; |
| 78 | + SparkBaseConfigAccessor turnConfigAccessor; |
74 | 79 |
|
75 | 80 | public SwerveModule(SwerveConfig config, ModuleType type, SparkBase drive, SparkBase turn, CANcoder turnEncoder, |
76 | 81 | int arrIndex, Supplier<Float> pitchDegSupplier, Supplier<Float> rollDegSupplier) { |
77 | 82 | driveMotorType = MotorControllerType.getMotorControllerType(drive); |
78 | 83 | turnMotorType = MotorControllerType.getMotorControllerType(turn); |
79 | 84 | driveConfig = driveMotorType.createConfig(); |
80 | 85 | turnConfig = turnMotorType.createConfig(); |
| 86 | + driveConfigAccessor = MotorControllerFactory.getConfigAccessor(drive); |
| 87 | + turnConfigAccessor = MotorControllerFactory.getConfigAccessor(turn); |
81 | 88 | //SmartDashboard.putNumber("Target Angle (deg)", 0.0); |
82 | 89 | String moduleString = type.toString(); |
83 | 90 | this.timer = new Timer(); |
@@ -121,18 +128,9 @@ public SwerveModule(SwerveConfig config, ModuleType type, SparkBase drive, Spark |
121 | 128 | config.drivekD[arrIndex]); |
122 | 129 |
|
123 | 130 | /* offset for 1 relative encoder count */ |
124 | | - switch(MotorControllerType.getMotorControllerType(drive)) { |
125 | | - case SPARK_MAX: |
126 | | - drivetoleranceMPerS = (1.0 |
127 | | - / (double)(((SparkMax)drive).configAccessor.encoder.getCountsPerRevolution()) * drivePositionFactor) |
128 | | - / Units.millisecondsToSeconds(((SparkMax)drive).configAccessor.signals.getPrimaryEncoderPositionPeriodMs() * ((SparkMax)drive).configAccessor.encoder.getQuadratureAverageDepth()); |
129 | | - break; |
130 | | - case SPARK_FLEX: |
131 | | - drivetoleranceMPerS = (1.0 |
132 | | - / (double)(((SparkFlex)drive).configAccessor.encoder.getCountsPerRevolution()) * drivePositionFactor) |
133 | | - / Units.millisecondsToSeconds(((SparkFlex)drive).configAccessor.signals.getPrimaryEncoderPositionPeriodMs() * ((SparkFlex)drive).configAccessor.encoder.getQuadratureAverageDepth()); |
134 | | - break; |
135 | | - } |
| 131 | + drivetoleranceMPerS = (1.0 |
| 132 | + / (double)(driveConfigAccessor.encoder.getCountsPerRevolution()) * drivePositionFactor) |
| 133 | + / Units.millisecondsToSeconds(driveConfigAccessor.signals.getPrimaryEncoderPositionPeriodMs() * driveConfigAccessor.encoder.getQuadratureAverageDepth()); |
136 | 134 | drivePIDController.setTolerance(drivetoleranceMPerS); |
137 | 135 |
|
138 | 136 | //System.out.println("Velocity Constant: " + (positionConstant / 60)); |
@@ -448,31 +446,8 @@ public void updateSmartDashboard() { |
448 | 446 | } |
449 | 447 |
|
450 | 448 | public void toggleMode() { |
451 | | - switch(MotorControllerType.getMotorControllerType(drive)) { |
452 | | - case SPARK_MAX: |
453 | | - switch (MotorControllerType.getMotorControllerType(turn)) { |
454 | | - case SPARK_MAX: |
455 | | - if (((SparkMax)drive).configAccessor.getIdleMode() == IdleMode.kBrake && ((SparkMax)turn).configAccessor.getIdleMode() == IdleMode.kCoast) coast(); |
456 | | - else brake(); |
457 | | - break; |
458 | | - case SPARK_FLEX: |
459 | | - if (((SparkMax)drive).configAccessor.getIdleMode() == IdleMode.kBrake && ((SparkFlex)turn).configAccessor.getIdleMode() == IdleMode.kCoast) coast(); |
460 | | - else brake(); |
461 | | - break; |
462 | | - } |
463 | | - case SPARK_FLEX: |
464 | | - switch (MotorControllerType.getMotorControllerType(turn)) { |
465 | | - case SPARK_MAX: |
466 | | - if (((SparkFlex)drive).configAccessor.getIdleMode() == IdleMode.kBrake && ((SparkMax)turn).configAccessor.getIdleMode() == IdleMode.kCoast) coast(); |
467 | | - else brake(); |
468 | | - break; |
469 | | - case SPARK_FLEX: |
470 | | - if (((SparkFlex)drive).configAccessor.getIdleMode() == IdleMode.kBrake && ((SparkFlex)turn).configAccessor.getIdleMode() == IdleMode.kCoast) coast(); |
471 | | - else brake(); |
472 | | - break; |
473 | | - } |
474 | | - break; |
475 | | - } |
| 449 | + if (driveConfigAccessor.getIdleMode() == IdleMode.kBrake && turnConfigAccessor.getIdleMode() == IdleMode.kCoast) coast(); |
| 450 | + else brake(); |
476 | 451 | } |
477 | 452 |
|
478 | 453 | public void brake() { |
|
0 commit comments