Skip to content

Commit 8e1a9a4

Browse files
author
Dheeraj Prakash
committed
remove subsystem parameter - can't use this in super()
1 parent 2d6cbd2 commit 8e1a9a4

File tree

3 files changed

+19
-7
lines changed

3 files changed

+19
-7
lines changed

src/main/java/org/hyperonline/hyperlib/controller/limits/DualLimitedController.java

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,13 @@ public class DualLimitedController implements SendableMotorController {
2424

2525
public DualLimitedController(SendableMotorController controller, DigitalInput forwardLimit, DigitalInput reverseLimit, DoublePreference forwardSpeed, DoublePreference reverseSpeed, Subsystem subsystem) {
2626
this.controller = controller;
27-
this.forwardController = new ForwardLimitedController(controller, forwardLimit, forwardSpeed, subsystem);
28-
this.reverseController = new ReverseLimitedController(controller, reverseLimit, reverseSpeed, subsystem);
27+
this.forwardController = new ForwardLimitedController(controller, forwardLimit, forwardSpeed);
28+
this.reverseController = new ReverseLimitedController(controller, reverseLimit, reverseSpeed);
29+
}
30+
31+
public void setSubsystem(Subsystem subsystem) {
32+
forwardController.setSubsystem(subsystem);
33+
reverseController.setSubsystem(subsystem);
2934
}
3035

3136
public boolean canMove(double speed) {

src/main/java/org/hyperonline/hyperlib/controller/limits/ForwardLimitedController.java

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,20 +39,23 @@ public class ForwardLimitedController implements SendableMotorController {
3939
/**
4040
* The subsystem the controller is being attached to
4141
*/
42-
private final Subsystem subsystem;
42+
private Subsystem subsystem;
4343

4444

4545
/**
4646
* Construct a new {@link ForwardLimitedController} from the given information.
4747
* @param controller the controller to limit
4848
* @param limit the forward limit switch
4949
* @param forwardSpeed the speed preference to move at
50-
* @param subsystem the subsystem the controller belongs to (to set requirement for commands)
5150
*/
52-
public ForwardLimitedController(SendableMotorController controller, DigitalInput limit, DoublePreference forwardSpeed, Subsystem subsystem) {
51+
public ForwardLimitedController(SendableMotorController controller, DigitalInput limit, DoublePreference forwardSpeed) {
5352
this.controller = controller;
5453
this.limit = limit;
5554
this.forwardSpeed = forwardSpeed;
55+
}
56+
57+
public void setSubsystem(Subsystem subsystem) {
58+
if (this.subsystem != null) throw new UnsupportedOperationException("Cannot replace already set subsystem.");
5659
this.subsystem = subsystem;
5760
}
5861

src/main/java/org/hyperonline/hyperlib/controller/limits/ReverseLimitedController.java

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,12 +25,16 @@ public class ReverseLimitedController implements SendableMotorController {
2525
private final SendableMotorController controller;
2626
private final DigitalInput limit;
2727
private final DoublePreference reverseSpeed;
28-
private final Subsystem subsystem;
28+
private Subsystem subsystem;
2929

30-
public ReverseLimitedController(SendableMotorController controller, DigitalInput limit, DoublePreference forwardSpeed, Subsystem subsystem) {
30+
public ReverseLimitedController(SendableMotorController controller, DigitalInput limit, DoublePreference forwardSpeed) {
3131
this.controller = controller;
3232
this.limit = limit;
3333
this.reverseSpeed = forwardSpeed;
34+
}
35+
36+
public void setSubsystem(Subsystem subsystem) {
37+
if (this.subsystem != null) throw new UnsupportedOperationException("Cannot replace already set subsystem.");
3438
this.subsystem = subsystem;
3539
}
3640

0 commit comments

Comments
 (0)