Skip to content
This repository was archived by the owner on Jan 13, 2025. It is now read-only.

Commit 3844c09

Browse files
committed
Separate interface for PIDSlotHelper.MotorCallbacks
1 parent 28a84c7 commit 3844c09

File tree

5 files changed

+57
-31
lines changed

5 files changed

+57
-31
lines changed

src/main/java/com/team766/hal/PIDSlotHelper.java

Lines changed: 29 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -18,34 +18,56 @@ private Slot(int slot) {
1818
this.slot = slot;
1919
this.pGain =
2020
new ObserveValue<Double>(
21-
ObserveValue.whenPresent((p) -> motor.setP(p, this.slot)));
21+
ObserveValue.whenPresent((p) -> motor.setP_Impl(p, this.slot)));
2222
this.iGain =
2323
new ObserveValue<Double>(
24-
ObserveValue.whenPresent((i) -> motor.setI(i, this.slot)));
24+
ObserveValue.whenPresent((i) -> motor.setI_Impl(i, this.slot)));
2525
this.dGain =
2626
new ObserveValue<Double>(
27-
ObserveValue.whenPresent((d) -> motor.setD(d, this.slot)));
27+
ObserveValue.whenPresent((d) -> motor.setD_Impl(d, this.slot)));
2828
this.ffGain =
2929
new ObserveValue<Double>(
30-
ObserveValue.whenPresent((ff) -> motor.setFF(ff, this.slot)));
30+
ObserveValue.whenPresent((ff) -> motor.setFF_Impl(ff, this.slot)));
3131
this.outputMin =
3232
new ObserveValue<Double>(ObserveValue.whenPresent((__) -> updateOutputRange()));
3333
this.outputMax =
3434
new ObserveValue<Double>(ObserveValue.whenPresent((__) -> updateOutputRange()));
3535
}
3636

3737
private void updateOutputRange() {
38-
motor.setOutputRange(
38+
motor.setOutputRange_Impl(
3939
outputMin.getValueProvider().valueOr(-1.0),
4040
outputMax.getValueProvider().valueOr(1.0),
4141
slot);
4242
}
4343
}
4444

45-
private final MotorController motor;
45+
/**
46+
* The methods of this interface match the semantics of the similarly-named methods in
47+
* {@link MotorController}, but it's important these set_Impl methods remain separate from the
48+
* MotorController methods, otherwise PIDSlotHelper will not work properly.
49+
* All of the MotorController methods should call PIDSlotHelper (rather than updating the motor
50+
* device directly) otherwise PIDSlotHelper's ObserveValues will not be updated, and they will
51+
* stay subscribed to the old ValueProvider.
52+
*/
53+
public static interface MotorCallbacks {
54+
int numPIDSlots();
55+
56+
void setP_Impl(double value, int slot);
57+
58+
void setI_Impl(double value, int slot);
59+
60+
void setD_Impl(double value, int slot);
61+
62+
void setFF_Impl(double value, int slot);
63+
64+
void setOutputRange_Impl(double minOutput, double maxOutput, int slot);
65+
}
66+
67+
private final MotorCallbacks motor;
4668
private final Slot[] slots;
4769

48-
public PIDSlotHelper(MotorController motor) {
70+
public PIDSlotHelper(MotorCallbacks motor) {
4971
this.motor = motor;
5072
final int size = motor.numPIDSlots();
5173
this.slots = new Slot[size];

src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,8 @@
1414
import java.util.function.Function;
1515
import java.util.function.Supplier;
1616

17-
public class CANSparkMaxMotorController extends CANSparkMax implements MotorController {
17+
public class CANSparkMaxMotorController extends CANSparkMax
18+
implements MotorController, PIDSlotHelper.MotorCallbacks {
1819

1920
private static final int NUM_PID_SLOTS = 2; // should be 4, only exposing 2 at this time.
2021

@@ -155,7 +156,7 @@ public void setP(ValueProvider<Double> value, int slot) {
155156
}
156157

157158
@Override
158-
public void setP(final double value, int slot) {
159+
public void setP_Impl(final double value, int slot) {
159160
revErrorToException(ExceptionTarget.LOG, getPIDController().setP(value, slot));
160161
}
161162

@@ -165,7 +166,7 @@ public void setI(ValueProvider<Double> value, int slot) {
165166
}
166167

167168
@Override
168-
public void setI(final double value, int slot) {
169+
public void setI_Impl(final double value, int slot) {
169170
revErrorToException(ExceptionTarget.LOG, getPIDController().setI(value, slot));
170171
}
171172

@@ -175,7 +176,7 @@ public void setD(ValueProvider<Double> value, int slot) {
175176
}
176177

177178
@Override
178-
public void setD(final double value, int slot) {
179+
public void setD_Impl(final double value, int slot) {
179180
revErrorToException(ExceptionTarget.LOG, getPIDController().setD(value, slot));
180181
}
181182

@@ -185,7 +186,7 @@ public void setFF(ValueProvider<Double> value, int slot) {
185186
}
186187

187188
@Override
188-
public void setFF(final double value, int slot) {
189+
public void setFF_Impl(final double value, int slot) {
189190
revErrorToException(ExceptionTarget.LOG, getPIDController().setFF(value, slot));
190191
}
191192

@@ -282,7 +283,7 @@ public void setOutputRange(
282283
}
283284

284285
@Override
285-
public void setOutputRange(final double minOutput, final double maxOutput, int slot) {
286+
public void setOutputRange_Impl(final double minOutput, final double maxOutput, int slot) {
286287
revErrorToException(
287288
ExceptionTarget.LOG, getPIDController().setOutputRange(minOutput, maxOutput, slot));
288289
}

src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,8 @@
2727
import com.team766.logging.LoggerExceptionUtils;
2828
import com.team766.logging.Severity;
2929

30-
public class CANTalonFxMotorController extends TalonFX implements MotorController {
30+
public class CANTalonFxMotorController extends TalonFX
31+
implements MotorController, PIDSlotHelper.MotorCallbacks {
3132

3233
private static final int NUM_PID_SLOTS = 2;
3334

@@ -194,7 +195,7 @@ public void setFF(ValueProvider<Double> value, int slot) {
194195
}
195196

196197
@Override
197-
public void setFF(final double value, int slot) {
198+
public void setFF_Impl(final double value, int slot) {
198199
refreshConfig();
199200
switch (slot) {
200201
case 0:
@@ -215,7 +216,7 @@ public void setP(final ValueProvider<Double> value, int slot) {
215216
}
216217

217218
@Override
218-
public void setP(final double value, int slot) {
219+
public void setP_Impl(final double value, int slot) {
219220
refreshConfig();
220221
switch (slot) {
221222
case 0:
@@ -236,7 +237,7 @@ public void setI(final ValueProvider<Double> value, int slot) {
236237
}
237238

238239
@Override
239-
public void setI(final double value, int slot) {
240+
public void setI_Impl(final double value, int slot) {
240241
refreshConfig();
241242
switch (slot) {
242243
case 0:
@@ -257,7 +258,7 @@ public void setD(final ValueProvider<Double> value, int slot) {
257258
}
258259

259260
@Override
260-
public void setD(final double value, int slot) {
261+
public void setD_Impl(final double value, int slot) {
261262
refreshConfig();
262263
switch (slot) {
263264
case 0:
@@ -313,7 +314,7 @@ public void setOutputRange(
313314
}
314315

315316
@Override
316-
public void setOutputRange(final double minOutput, final double maxOutput, int slot) {
317+
public void setOutputRange_Impl(final double minOutput, final double maxOutput, int slot) {
317318
if (slot != 0) {
318319
Logger.get(Category.HAL)
319320
.logRaw(

src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,8 @@
1313
import com.team766.logging.LoggerExceptionUtils;
1414
import com.team766.logging.Severity;
1515

16-
public class CANTalonMotorController extends BaseCTREMotorController implements MotorController {
16+
public class CANTalonMotorController extends BaseCTREMotorController
17+
implements MotorController, PIDSlotHelper.MotorCallbacks {
1718
private static final int NUM_PID_SLOTS = 2;
1819

1920
private WPI_TalonSRX m_device;
@@ -139,22 +140,22 @@ public void setD(ValueProvider<Double> value, int slot) {
139140
}
140141

141142
@Override
142-
public void setFF(final double value, int slot) {
143+
public void setFF_Impl(final double value, int slot) {
143144
errorCodeToException(ExceptionTarget.LOG, m_device.config_kF(slot, value, TIMEOUT_MS));
144145
}
145146

146147
@Override
147-
public void setP(final double value, int slot) {
148+
public void setP_Impl(final double value, int slot) {
148149
errorCodeToException(ExceptionTarget.LOG, m_device.config_kP(slot, value));
149150
}
150151

151152
@Override
152-
public void setI(final double value, int slot) {
153+
public void setI_Impl(final double value, int slot) {
153154
errorCodeToException(ExceptionTarget.LOG, m_device.config_kI(slot, value));
154155
}
155156

156157
@Override
157-
public void setD(final double value, int slot) {
158+
public void setD_Impl(final double value, int slot) {
158159
errorCodeToException(ExceptionTarget.LOG, m_device.config_kD(slot, value));
159160
}
160161

@@ -176,7 +177,7 @@ public void setOutputRange(
176177
}
177178

178179
@Override
179-
public void setOutputRange(final double minOutput, final double maxOutput, int slot) {
180+
public void setOutputRange_Impl(final double minOutput, final double maxOutput, int slot) {
180181
if (slot != 0) {
181182
Logger.get(Category.HAL)
182183
.logRaw(

src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,8 @@
1313
import com.team766.logging.LoggerExceptionUtils;
1414
import com.team766.logging.Severity;
1515

16-
public class CANVictorMotorController extends BaseCTREMotorController implements MotorController {
16+
public class CANVictorMotorController extends BaseCTREMotorController
17+
implements MotorController, PIDSlotHelper.MotorCallbacks {
1718
private static final int NUM_PID_SLOTS = 2;
1819

1920
private final WPI_VictorSPX m_device;
@@ -121,7 +122,7 @@ public void setFF(final ValueProvider<Double> value, int slot) {
121122
}
122123

123124
@Override
124-
public void setFF(final double value, int slot) {
125+
public void setFF_Impl(final double value, int slot) {
125126
errorCodeToException(ExceptionTarget.LOG, m_device.config_kF(slot, value, TIMEOUT_MS));
126127
}
127128

@@ -161,7 +162,7 @@ public void setP(final ValueProvider<Double> value, int slot) {
161162
}
162163

163164
@Override
164-
public void setP(final double value, int slot) {
165+
public void setP_Impl(final double value, int slot) {
165166
errorCodeToException(ExceptionTarget.LOG, m_device.config_kP(slot, value, TIMEOUT_MS));
166167
}
167168

@@ -171,7 +172,7 @@ public void setI(final ValueProvider<Double> value, int slot) {
171172
}
172173

173174
@Override
174-
public void setI(final double value, int slot) {
175+
public void setI_Impl(final double value, int slot) {
175176
errorCodeToException(ExceptionTarget.LOG, m_device.config_kI(slot, value, TIMEOUT_MS));
176177
}
177178

@@ -181,7 +182,7 @@ public void setD(final ValueProvider<Double> value, int slot) {
181182
}
182183

183184
@Override
184-
public void setD(final double value, int slot) {
185+
public void setD_Impl(final double value, int slot) {
185186
errorCodeToException(ExceptionTarget.LOG, m_device.config_kD(slot, value, TIMEOUT_MS));
186187
}
187188

@@ -203,7 +204,7 @@ public void setOutputRange(
203204
}
204205

205206
@Override
206-
public void setOutputRange(final double minOutput, final double maxOutput, int slot) {
207+
public void setOutputRange_Impl(final double minOutput, final double maxOutput, int slot) {
207208
if (slot != 0) {
208209
Logger.get(Category.HAL)
209210
.logRaw(

0 commit comments

Comments
 (0)