Skip to content

Commit 3bc5710

Browse files
committed
feat: create roller hold speed method
Signed-off-by: Dasun Abeykoon <[email protected]>
1 parent 30e4293 commit 3bc5710

File tree

2 files changed

+26
-0
lines changed

2 files changed

+26
-0
lines changed

src/main/java/org/frc6423/lib/subsystems/Roller.java

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
import edu.wpi.first.epilogue.Logged;
1010
import edu.wpi.first.math.filter.LinearFilter;
1111
import edu.wpi.first.wpilibj2.command.Command;
12+
import edu.wpi.first.wpilibj2.command.Commands;
1213
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1314
import java.util.function.DoubleSupplier;
1415

@@ -87,6 +88,22 @@ protected Command runSpeed(double speedRpm) {
8788
return runSpeed(() -> speedRpm);
8889
}
8990

91+
/**
92+
* Hold rollers at current speed
93+
*
94+
* @return {@link Command}
95+
*/
96+
protected Command holdSpeed() {
97+
return Commands.sequence(
98+
this.run(
99+
() -> {
100+
var currentSpeed = hardware.getSpeedRpm();
101+
hardware.setSpeed(currentSpeed);
102+
})
103+
.until(() -> true),
104+
this.run(() -> {}));
105+
}
106+
90107
@Override
91108
public void close() throws Exception {
92109
hardware.close();

src/main/java/org/frc6423/robot/subsystems/arm/ArmRoller.java

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -66,4 +66,13 @@ public Command runSpeed(DoubleSupplier speedRpm) {
6666
public Command runSpeed(double speedRpm) {
6767
return super.runSpeed(speedRpm);
6868
}
69+
70+
/**
71+
* Hold roller at specified speed
72+
*
73+
* @return {@link Command}
74+
*/
75+
public Command holdSpeed() {
76+
return super.holdSpeed();
77+
}
6978
}

0 commit comments

Comments
 (0)