[wpilib] Rename DoubleSolenoid.Value constants to all caps

This commit is contained in:
Peter Johnson
2026-03-17 17:10:58 -07:00
parent c5738fcbad
commit d86a745328
32 changed files with 155 additions and 155 deletions

View File

@@ -4,8 +4,8 @@
package org.wpilib.examples.hatchbotinlined.subsystems;
import static org.wpilib.hardware.pneumatic.DoubleSolenoid.Value.kForward;
import static org.wpilib.hardware.pneumatic.DoubleSolenoid.Value.kReverse;
import static org.wpilib.hardware.pneumatic.DoubleSolenoid.Value.FORWARD;
import static org.wpilib.hardware.pneumatic.DoubleSolenoid.Value.REVERSE;
import org.wpilib.command2.Command;
import org.wpilib.command2.SubsystemBase;
@@ -26,19 +26,19 @@ public class HatchSubsystem extends SubsystemBase {
/** Grabs the hatch. */
public Command grabHatchCommand() {
// implicitly require `this`
return this.runOnce(() -> m_hatchSolenoid.set(kForward));
return this.runOnce(() -> m_hatchSolenoid.set(FORWARD));
}
/** Releases the hatch. */
public Command releaseHatchCommand() {
// implicitly require `this`
return this.runOnce(() -> m_hatchSolenoid.set(kReverse));
return this.runOnce(() -> m_hatchSolenoid.set(REVERSE));
}
@Override
public void initSendable(SendableBuilder builder) {
super.initSendable(builder);
// Publish the solenoid state to telemetry.
builder.addBooleanProperty("extended", () -> m_hatchSolenoid.get() == kForward, null);
builder.addBooleanProperty("extended", () -> m_hatchSolenoid.get() == FORWARD, null);
}
}

View File

@@ -4,8 +4,8 @@
package org.wpilib.examples.hatchbottraditional.subsystems;
import static org.wpilib.hardware.pneumatic.DoubleSolenoid.Value.kForward;
import static org.wpilib.hardware.pneumatic.DoubleSolenoid.Value.kReverse;
import static org.wpilib.hardware.pneumatic.DoubleSolenoid.Value.FORWARD;
import static org.wpilib.hardware.pneumatic.DoubleSolenoid.Value.REVERSE;
import org.wpilib.command2.SubsystemBase;
import org.wpilib.examples.hatchbottraditional.Constants.HatchConstants;
@@ -24,18 +24,18 @@ public class HatchSubsystem extends SubsystemBase {
/** Grabs the hatch. */
public void grabHatch() {
m_hatchSolenoid.set(kForward);
m_hatchSolenoid.set(FORWARD);
}
/** Releases the hatch. */
public void releaseHatch() {
m_hatchSolenoid.set(kReverse);
m_hatchSolenoid.set(REVERSE);
}
@Override
public void initSendable(SendableBuilder builder) {
super.initSendable(builder);
// Publish the solenoid state to telemetry.
builder.addBooleanProperty("extended", () -> m_hatchSolenoid.get() == kForward, null);
builder.addBooleanProperty("extended", () -> m_hatchSolenoid.get() == FORWARD, null);
}
}

View File

@@ -28,7 +28,7 @@ public class Intake extends SubsystemBase {
/** Returns a command that deploys the intake, and then runs the intake motor indefinitely. */
public Command intakeCommand() {
return runOnce(() -> m_pistons.set(DoubleSolenoid.Value.kForward))
return runOnce(() -> m_pistons.set(DoubleSolenoid.Value.FORWARD))
.andThen(run(() -> m_motor.setDutyCycle(1.0)))
.withName("Intake");
}
@@ -38,7 +38,7 @@ public class Intake extends SubsystemBase {
return runOnce(
() -> {
m_motor.disable();
m_pistons.set(DoubleSolenoid.Value.kReverse);
m_pistons.set(DoubleSolenoid.Value.REVERSE);
})
.withName("Retract");
}

View File

@@ -24,11 +24,11 @@ public class Intake implements AutoCloseable {
}
public void deploy() {
m_piston.set(DoubleSolenoid.Value.kForward);
m_piston.set(DoubleSolenoid.Value.FORWARD);
}
public void retract() {
m_piston.set(DoubleSolenoid.Value.kReverse);
m_piston.set(DoubleSolenoid.Value.REVERSE);
m_motor.setDutyCycle(0); // turn off the motor
}
@@ -41,7 +41,7 @@ public class Intake implements AutoCloseable {
}
public boolean isDeployed() {
return m_piston.get() == DoubleSolenoid.Value.kForward;
return m_piston.get() == DoubleSolenoid.Value.FORWARD;
}
@Override

View File

@@ -79,9 +79,9 @@ public class Robot extends TimedRobot {
* If a button is pressed, set the solenoid to the respective channel.
*/
if (m_stick.getRawButtonPressed(kDoubleSolenoidForwardButton)) {
m_doubleSolenoid.set(DoubleSolenoid.Value.kForward);
m_doubleSolenoid.set(DoubleSolenoid.Value.FORWARD);
} else if (m_stick.getRawButtonPressed(kDoubleSolenoidReverseButton)) {
m_doubleSolenoid.set(DoubleSolenoid.Value.kReverse);
m_doubleSolenoid.set(DoubleSolenoid.Value.REVERSE);
}
// On button press, toggle the compressor.

View File

@@ -60,12 +60,12 @@ class IntakeTest {
@Test
void retractTest() {
m_intake.retract();
assertEquals(DoubleSolenoid.Value.kReverse, m_simPiston.get());
assertEquals(DoubleSolenoid.Value.REVERSE, m_simPiston.get());
}
@Test
void deployTest() {
m_intake.deploy();
assertEquals(DoubleSolenoid.Value.kForward, m_simPiston.get());
assertEquals(DoubleSolenoid.Value.FORWARD, m_simPiston.get());
}
}