Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Change all the run to runOnce #90

Open
wants to merge 6 commits into
base: dev
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions src/main/kotlin/frc/robot/RobotContainer.kt
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ object RobotContainer {
driverController().back()
.whileTrue(gripper.setRollerPower(0.4))
.onFalse(gripper.stop())
driverController().start().whileTrue(intake.reset())
driverController().start().whileTrue(intake.reset()).onFalse(intake.finishReset())
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Instead, intake.reset() can use runEnd() decorator.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not really sure what is the decorator you're referring to.
Also i think it doesn't matter that much.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not really sure what is the decorator you're referring to.

How lucky we are to have an API reference 🙃.
I think it's nice because otherwise you duplicate code, and this logic IMO should be in the subsystem.

Copy link
Contributor Author

@rakrakon rakrakon Nov 27, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You mean a runend command? Otherwise I'm not really sure what you're referring to exists.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes :)


driverController().povUp().whileTrue(climb.openClimb())
driverController().povDown().whileTrue(climb.closeClimb())
Expand All @@ -123,7 +123,7 @@ object RobotContainer {
operatorController().cross().onTrue(gripper.enableSensor())
operatorController().circle().onTrue(gripper.disableSensor())

operatorController().options().whileTrue(intake.reset())
operatorController().options().whileTrue(intake.reset()).onFalse(intake.finishReset())
}

fun getAutonomousCommand(): Command = autoChooser.get()
Expand Down
8 changes: 5 additions & 3 deletions src/main/kotlin/frc/robot/subsystems/climb/Climb.kt
Original file line number Diff line number Diff line change
Expand Up @@ -38,15 +38,17 @@ class Climb private constructor(private val io: ClimbIO) : SubsystemBase() {
}

fun unlock(): Command {
return Commands.run(io::openStopper).until { isStopperStuck }.andThen(io::disableStopper)
return Commands.runOnce(io::openStopper).andThen(Commands.waitUntil { isStopperStuck })
.andThen(io::disableStopper)
}

fun lock(): Command {
return Commands.run(io::closeStopper).until { isStopperStuck }.andThen(io::disableStopper)
return Commands.runOnce(io::closeStopper).andThen(Commands.waitUntil { isStopperStuck })
.andThen(io::disableStopper)
}

fun setPower(power: DoubleSupplier): Command {
return run { io.setPower(power.asDouble) }
return runOnce { io.setPower(power.asDouble) }
}

fun stop(): Command = setPower { 0.0 }.withTimeout(0.02)
Expand Down
4 changes: 2 additions & 2 deletions src/main/kotlin/frc/robot/subsystems/conveyor/Conveyor.kt
Original file line number Diff line number Diff line change
Expand Up @@ -46,13 +46,13 @@ class Conveyor private constructor(private val io: ConveyorIO) : SubsystemBase()
timer.reset()
}

fun setVelocity(velocitySupplier: () -> AngularVelocity): Command = run {
fun setVelocity(velocitySupplier: () -> AngularVelocity): Command = runOnce {
val velocity = velocitySupplier.invoke()
velocitySetpoint = velocity
io.setVelocity(velocity)
}

fun setVelocity(velocity: AngularVelocity): Command = run {
fun setVelocity(velocity: AngularVelocity): Command = runOnce {
velocitySetpoint = velocity
io.setVelocity(velocity)
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/kotlin/frc/robot/subsystems/gripper/Gripper.kt
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class Gripper private constructor(private val io: GripperIO) : SubsystemBase() {
}

fun setRollerPower(power: Double): Command {
return run {
return runOnce {
rollerPowerSetPoint = power
io.setRollerMotorPower(power)
}.withName("Set Roller Power")
Expand Down
2 changes: 1 addition & 1 deletion src/main/kotlin/frc/robot/subsystems/hood/Hood.kt
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class Hood private constructor(private val io: HoodIO) : SubsystemBase() {
}

fun setAngle(angleSupplier: () -> Angle): Command {
return run {
return runOnce {
val angle = angleSupplier.invoke()
angleSetpoint = angle
io.setAngle(angle)
Expand Down
14 changes: 8 additions & 6 deletions src/main/kotlin/frc/robot/subsystems/intake/Intake.kt
Original file line number Diff line number Diff line change
Expand Up @@ -83,12 +83,14 @@ class Intake private constructor(private val io: IntakeIO) : SubsystemBase() {
}

fun reset(): Command {
return Commands.run({ io.setAnglePower(-0.3) }).finallyDo(
Runnable {
io.resetEncoder()
io.setAnglePower(0.0)
}
)
return Commands.runOnce({ io.setAnglePower(-0.3) })
}

fun finishReset(): Command {
return Commands.runOnce({
io.resetEncoder()
io.setAnglePower(0.0)
})
}

override fun periodic() {
Expand Down
2 changes: 1 addition & 1 deletion src/main/kotlin/frc/robot/subsystems/shooter/Shooter.kt
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ class Shooter private constructor(private val io: ShooterIO) : SubsystemBase() {
}

fun setVelocity(velocitySupplier: () -> AngularVelocity): Command {
return run {
return runOnce {
val velocity = velocitySupplier.invoke()
topVelocitySetpoint = velocity
bottomVelocitySetpoint = velocity
Expand Down
2 changes: 1 addition & 1 deletion src/main/kotlin/frc/robot/subsystems/swerve/ModuleIOSim.kt
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ class ModuleIOSim() : ModuleIO {
}

override fun checkModule(): Command? {
return Commands.run(
return Commands.runOnce(
{
driveControlRequest.withVelocity(0.8 * SwerveConstants.MAX_X_Y_VELOCITY)
driveMotor.setControl(driveControlRequest)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ class ModuleIOSparkMax(
}

override fun checkModule(): Command? {
return Commands.run(
return Commands.runOnce(
{
driveMotor.set(0.8)
angleMotor.set(0.2)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ class ModuleIOTalonFX(
}

override fun checkModule(): Command? {
return Commands.run(
return Commands.runOnce(
{
driveMotor.set(0.8)
angleMotor.set(0.2)
Expand Down