From d86a74532805584b179cfb3edbfa8cd45e8d4188 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Tue, 17 Mar 2026 17:10:58 -0700 Subject: [PATCH] [wpilib] Rename DoubleSolenoid.Value constants to all caps --- .../subsystems/hatchsubsystem.py | 4 +-- .../subsystems/hatchsubsystem.py | 4 +-- .../RapidReactCommandBot/subsystems/intake.py | 4 +-- robotpyExamples/Solenoid/robot.py | 4 +-- robotpyExamples/UnitTest/constants.py | 10 +++--- robotpyExamples/UnitTest/robot.py | 4 +-- robotpyExamples/UnitTest/subsystems/intake.py | 12 +++---- .../cpp/hardware/pneumatic/DoubleSolenoid.cpp | 30 ++++++++--------- .../cpp/simulation/DoubleSolenoidSim.cpp | 10 +++--- .../wpi/hardware/pneumatic/DoubleSolenoid.hpp | 6 ++-- .../native/cpp/DoubleSolenoidTestCTRE.cpp | 22 ++++++------- .../test/native/cpp/DoubleSolenoidTestREV.cpp | 22 ++++++------- .../native/cpp/simulation/CTREPCMSimTest.cpp | 6 ++-- .../native/cpp/simulation/REVPHSimTest.cpp | 6 ++-- .../cpp/subsystems/HatchSubsystem.cpp | 6 ++-- .../cpp/subsystems/HatchSubsystem.cpp | 6 ++-- .../cpp/subsystems/Intake.cpp | 4 +-- .../UnitTest/cpp/subsystems/Intake.cpp | 6 ++-- .../main/cpp/snippets/Solenoid/cpp/Robot.cpp | 4 +-- .../UnitTest/cpp/subsystems/IntakeTest.cpp | 4 +-- .../hardware/pneumatic/DoubleSolenoid.java | 32 +++++++++---------- .../wpilib/simulation/DoubleSolenoidSim.java | 10 +++--- .../pneumatic/DoubleSolenoidTestCTRE.java | 22 ++++++------- .../pneumatic/DoubleSolenoidTestREV.java | 22 ++++++------- .../org/wpilib/simulation/CTREPCMSimTest.java | 6 ++-- .../org/wpilib/simulation/REVPHSimTest.java | 6 ++-- .../subsystems/HatchSubsystem.java | 10 +++--- .../subsystems/HatchSubsystem.java | 10 +++--- .../subsystems/Intake.java | 4 +-- .../examples/unittest/subsystems/Intake.java | 6 ++-- .../org/wpilib/snippets/solenoid/Robot.java | 4 +-- .../unittest/subsystems/IntakeTest.java | 4 +-- 32 files changed, 155 insertions(+), 155 deletions(-) diff --git a/robotpyExamples/HatchbotInlined/subsystems/hatchsubsystem.py b/robotpyExamples/HatchbotInlined/subsystems/hatchsubsystem.py index 55f05e1566..1764e9caf4 100644 --- a/robotpyExamples/HatchbotInlined/subsystems/hatchsubsystem.py +++ b/robotpyExamples/HatchbotInlined/subsystems/hatchsubsystem.py @@ -23,11 +23,11 @@ class HatchSubsystem(commands2.Subsystem): def grabHatch(self) -> commands2.Command: """Grabs the hatch""" return commands2.cmd.runOnce( - lambda: self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kForward), self + lambda: self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.FORWARD), self ) def releaseHatch(self) -> commands2.Command: """Releases the hatch""" return commands2.cmd.runOnce( - lambda: self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kReverse), self + lambda: self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.REVERSE), self ) diff --git a/robotpyExamples/HatchbotTraditional/subsystems/hatchsubsystem.py b/robotpyExamples/HatchbotTraditional/subsystems/hatchsubsystem.py index 3070e730ce..daf334acfe 100644 --- a/robotpyExamples/HatchbotTraditional/subsystems/hatchsubsystem.py +++ b/robotpyExamples/HatchbotTraditional/subsystems/hatchsubsystem.py @@ -21,8 +21,8 @@ class HatchSubsystem(commands2.Subsystem): def grabHatch(self) -> None: """Grabs the hatch""" - self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kForward) + self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.FORWARD) def releaseHatch(self) -> None: """Releases the hatch""" - self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kReverse) + self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.REVERSE) diff --git a/robotpyExamples/RapidReactCommandBot/subsystems/intake.py b/robotpyExamples/RapidReactCommandBot/subsystems/intake.py index 234c620bb3..e5b44778ff 100644 --- a/robotpyExamples/RapidReactCommandBot/subsystems/intake.py +++ b/robotpyExamples/RapidReactCommandBot/subsystems/intake.py @@ -28,7 +28,7 @@ class Intake(Subsystem): indefinitely. """ return ( - self.runOnce(lambda: self.pistons.set(wpilib.DoubleSolenoid.Value.kForward)) + self.runOnce(lambda: self.pistons.set(wpilib.DoubleSolenoid.Value.FORWARD)) .andThen(self.run(lambda: self.motor.set(1.0))) .withName("Intake") ) @@ -38,6 +38,6 @@ class Intake(Subsystem): return self.runOnce( lambda: ( self.motor.disable(), - self.pistons.set(wpilib.DoubleSolenoid.Value.kReverse), + self.pistons.set(wpilib.DoubleSolenoid.Value.REVERSE), ) ).withName("Retract") diff --git a/robotpyExamples/Solenoid/robot.py b/robotpyExamples/Solenoid/robot.py index 45312b59dd..af088eca70 100644 --- a/robotpyExamples/Solenoid/robot.py +++ b/robotpyExamples/Solenoid/robot.py @@ -86,9 +86,9 @@ class MyRobot(wpilib.TimedRobot): # If a button is pressed, set the solenoid to the respective channel. if self.joystick.getRawButtonPressed(kDoubleSolenoidForwardButton): - self.doubleSolenoid.set(wpilib.DoubleSolenoid.Value.kForward) + self.doubleSolenoid.set(wpilib.DoubleSolenoid.Value.FORWARD) elif self.joystick.getRawButtonPressed(kDoubleSolenoidReverseButton): - self.doubleSolenoid.set(wpilib.DoubleSolenoid.Value.kReverse) + self.doubleSolenoid.set(wpilib.DoubleSolenoid.Value.REVERSE) # On button press, toggle the compressor. if self.joystick.getRawButtonPressed(kCompressorButton): diff --git a/robotpyExamples/UnitTest/constants.py b/robotpyExamples/UnitTest/constants.py index 4db5e444df..662633904c 100644 --- a/robotpyExamples/UnitTest/constants.py +++ b/robotpyExamples/UnitTest/constants.py @@ -6,11 +6,11 @@ class IntakeConstants: - kMotorPort = 1 + MOTOR_PORT = 1 - kPistonFwdChannel = 0 - kPistonRevChannel = 1 - kIntakeVelocity = 0.5 + PISTON_FWD_CHANNEL = 0 + PISTON_REV_CHANNEL = 1 + INTAKE_VELOCITY = 0.5 -kJoystickIndex = 0 +JOYSTICK_INDEX = 0 diff --git a/robotpyExamples/UnitTest/robot.py b/robotpyExamples/UnitTest/robot.py index b1968f62f2..baca817b5d 100644 --- a/robotpyExamples/UnitTest/robot.py +++ b/robotpyExamples/UnitTest/robot.py @@ -21,13 +21,13 @@ class MyRobot(wpilib.TimedRobot): def __init__(self) -> None: super().__init__() self.intake = Intake() - self.joystick = wpilib.Joystick(constants.kJoystickIndex) + self.joystick = wpilib.Joystick(constants.JOYSTICK_INDEX) def teleopPeriodic(self) -> None: """This function is called periodically during operator control.""" # Activate the intake while the trigger is held if self.joystick.getTrigger(): - self.intake.activate(constants.IntakeConstants.kIntakeVelocity) + self.intake.activate(constants.IntakeConstants.INTAKE_VELOCITY) else: self.intake.activate(0) diff --git a/robotpyExamples/UnitTest/subsystems/intake.py b/robotpyExamples/UnitTest/subsystems/intake.py index a4007c2eef..9b585e6ace 100644 --- a/robotpyExamples/UnitTest/subsystems/intake.py +++ b/robotpyExamples/UnitTest/subsystems/intake.py @@ -11,19 +11,19 @@ from constants import IntakeConstants class Intake: def __init__(self) -> None: - self.motor = wpilib.PWMSparkMax(IntakeConstants.kMotorPort) + self.motor = wpilib.PWMSparkMax(IntakeConstants.MOTOR_PORT) self.piston = wpilib.DoubleSolenoid( 0, wpilib.PneumaticsModuleType.CTREPCM, - IntakeConstants.kPistonFwdChannel, - IntakeConstants.kPistonRevChannel, + IntakeConstants.PISTON_FWD_CHANNEL, + IntakeConstants.PISTON_REV_CHANNEL, ) def deploy(self) -> None: - self.piston.setDutyCycle(wpilib.DoubleSolenoid.Value.kForward) + self.piston.setDutyCycle(wpilib.DoubleSolenoid.Value.FORWARD) def retract(self) -> None: - self.piston.setDutyCycle(wpilib.DoubleSolenoid.Value.kReverse) + self.piston.setDutyCycle(wpilib.DoubleSolenoid.Value.REVERSE) self.motor.setDutyCycle(0) # turn off the motor def activate(self, velocity: float) -> None: @@ -33,4 +33,4 @@ class Intake: self.motor.setDutyCycle(0) def isDeployed(self) -> bool: - return self.piston.get() == wpilib.DoubleSolenoid.Value.kForward + return self.piston.get() == wpilib.DoubleSolenoid.Value.FORWARD diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp index 5f335a9732..6693eaa732 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp @@ -72,13 +72,13 @@ void DoubleSolenoid::Set(Value value) { int setValue = 0; switch (value) { - case kOff: + case OFF: setValue = 0; break; - case kForward: + case FORWARD: setValue = m_forwardMask; break; - case kReverse: + case REVERSE: setValue = m_reverseMask; break; } @@ -90,21 +90,21 @@ DoubleSolenoid::Value DoubleSolenoid::Get() const { auto values = m_module->GetSolenoids(); if ((values & m_forwardMask) != 0) { - return Value::kForward; + return Value::FORWARD; } else if ((values & m_reverseMask) != 0) { - return Value::kReverse; + return Value::REVERSE; } else { - return Value::kOff; + return Value::OFF; } } void DoubleSolenoid::Toggle() { Value value = Get(); - if (value == kForward) { - Set(kReverse); - } else if (value == kReverse) { - Set(kForward); + if (value == FORWARD) { + Set(REVERSE); + } else if (value == REVERSE) { + Set(FORWARD); } } @@ -131,20 +131,20 @@ void DoubleSolenoid::InitSendable(wpi::util::SendableBuilder& builder) { "Value", [=, this](wpi::util::SmallVectorImpl& buf) -> std::string_view { switch (Get()) { - case kForward: + case FORWARD: return "Forward"; - case kReverse: + case REVERSE: return "Reverse"; default: return "Off"; } }, [=, this](std::string_view value) { - Value lvalue = kOff; + Value lvalue = OFF; if (value == "Forward") { - lvalue = kForward; + lvalue = FORWARD; } else if (value == "Reverse") { - lvalue = kReverse; + lvalue = REVERSE; } Set(lvalue); }); diff --git a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp index c3b3b2a7c8..e2dd154979 100644 --- a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp @@ -33,17 +33,17 @@ DoubleSolenoid::Value DoubleSolenoidSim::Get() const { bool fwdState = m_module->GetSolenoidOutput(m_fwd); bool revState = m_module->GetSolenoidOutput(m_rev); if (fwdState && !revState) { - return DoubleSolenoid::Value::kForward; + return DoubleSolenoid::Value::FORWARD; } else if (!fwdState && revState) { - return DoubleSolenoid::Value::kReverse; + return DoubleSolenoid::Value::REVERSE; } else { - return DoubleSolenoid::Value::kOff; + return DoubleSolenoid::Value::OFF; } } void DoubleSolenoidSim::Set(DoubleSolenoid::Value output) { - m_module->SetSolenoidOutput(m_fwd, output == DoubleSolenoid::Value::kForward); - m_module->SetSolenoidOutput(m_rev, output == DoubleSolenoid::Value::kReverse); + m_module->SetSolenoidOutput(m_fwd, output == DoubleSolenoid::Value::FORWARD); + m_module->SetSolenoidOutput(m_rev, output == DoubleSolenoid::Value::REVERSE); } std::shared_ptr DoubleSolenoidSim::GetModuleSim() const { diff --git a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/DoubleSolenoid.hpp b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/DoubleSolenoid.hpp index 3152dbb3c9..cdd9b76a61 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/DoubleSolenoid.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/DoubleSolenoid.hpp @@ -29,11 +29,11 @@ class DoubleSolenoid : public wpi::util::Sendable, */ enum Value { /// Off position. - kOff, + OFF, /// Forward position. - kForward, + FORWARD, /// Reverse position. - kReverse + REVERSE }; /** diff --git a/wpilibc/src/test/native/cpp/DoubleSolenoidTestCTRE.cpp b/wpilibc/src/test/native/cpp/DoubleSolenoidTestCTRE.cpp index 63a7157355..04195b79e0 100644 --- a/wpilibc/src/test/native/cpp/DoubleSolenoidTestCTRE.cpp +++ b/wpilibc/src/test/native/cpp/DoubleSolenoidTestCTRE.cpp @@ -12,14 +12,14 @@ namespace wpi { TEST(DoubleSolenoidCTRETest, ValidInitialization) { DoubleSolenoid solenoid{0, 3, wpi::PneumaticsModuleType::CTREPCM, 2, 3}; - solenoid.Set(DoubleSolenoid::kReverse); - EXPECT_EQ(DoubleSolenoid::kReverse, solenoid.Get()); + solenoid.Set(DoubleSolenoid::REVERSE); + EXPECT_EQ(DoubleSolenoid::REVERSE, solenoid.Get()); - solenoid.Set(DoubleSolenoid::kForward); - EXPECT_EQ(DoubleSolenoid::kForward, solenoid.Get()); + solenoid.Set(DoubleSolenoid::FORWARD); + EXPECT_EQ(DoubleSolenoid::FORWARD, solenoid.Get()); - solenoid.Set(DoubleSolenoid::kOff); - EXPECT_EQ(DoubleSolenoid::kOff, solenoid.Get()); + solenoid.Set(DoubleSolenoid::OFF); + EXPECT_EQ(DoubleSolenoid::OFF, solenoid.Get()); } TEST(DoubleSolenoidCTRETest, ThrowForwardPortAlreadyInitialized) { @@ -48,18 +48,18 @@ TEST(DoubleSolenoidCTRETest, ThrowBothPortsAlreadyInitialized) { TEST(DoubleSolenoidCTRETest, Toggle) { DoubleSolenoid solenoid{0, 4, wpi::PneumaticsModuleType::CTREPCM, 2, 3}; // Bootstrap it into reverse - solenoid.Set(DoubleSolenoid::kReverse); + solenoid.Set(DoubleSolenoid::REVERSE); solenoid.Toggle(); - EXPECT_EQ(DoubleSolenoid::kForward, solenoid.Get()); + EXPECT_EQ(DoubleSolenoid::FORWARD, solenoid.Get()); solenoid.Toggle(); - EXPECT_EQ(DoubleSolenoid::kReverse, solenoid.Get()); + EXPECT_EQ(DoubleSolenoid::REVERSE, solenoid.Get()); // Of shouldn't do anything on toggle - solenoid.Set(DoubleSolenoid::kOff); + solenoid.Set(DoubleSolenoid::OFF); solenoid.Toggle(); - EXPECT_EQ(DoubleSolenoid::kOff, solenoid.Get()); + EXPECT_EQ(DoubleSolenoid::OFF, solenoid.Get()); } TEST(DoubleSolenoidCTRETest, InvalidForwardPort) { diff --git a/wpilibc/src/test/native/cpp/DoubleSolenoidTestREV.cpp b/wpilibc/src/test/native/cpp/DoubleSolenoidTestREV.cpp index d4c4b05260..07713c68ec 100644 --- a/wpilibc/src/test/native/cpp/DoubleSolenoidTestREV.cpp +++ b/wpilibc/src/test/native/cpp/DoubleSolenoidTestREV.cpp @@ -12,14 +12,14 @@ namespace wpi { TEST(DoubleSolenoidREVTest, ValidInitialization) { DoubleSolenoid solenoid{0, 3, wpi::PneumaticsModuleType::CTREPCM, 2, 3}; - solenoid.Set(DoubleSolenoid::kReverse); - EXPECT_EQ(DoubleSolenoid::kReverse, solenoid.Get()); + solenoid.Set(DoubleSolenoid::REVERSE); + EXPECT_EQ(DoubleSolenoid::REVERSE, solenoid.Get()); - solenoid.Set(DoubleSolenoid::kForward); - EXPECT_EQ(DoubleSolenoid::kForward, solenoid.Get()); + solenoid.Set(DoubleSolenoid::FORWARD); + EXPECT_EQ(DoubleSolenoid::FORWARD, solenoid.Get()); - solenoid.Set(DoubleSolenoid::kOff); - EXPECT_EQ(DoubleSolenoid::kOff, solenoid.Get()); + solenoid.Set(DoubleSolenoid::OFF); + EXPECT_EQ(DoubleSolenoid::OFF, solenoid.Get()); } TEST(DoubleSolenoidREVTest, ThrowForwardPortAlreadyInitialized) { @@ -48,18 +48,18 @@ TEST(DoubleSolenoidREVTest, ThrowBothPortsAlreadyInitialized) { TEST(DoubleSolenoidREVTest, Toggle) { DoubleSolenoid solenoid{0, 4, wpi::PneumaticsModuleType::CTREPCM, 2, 3}; // Bootstrap it into reverse - solenoid.Set(DoubleSolenoid::kReverse); + solenoid.Set(DoubleSolenoid::REVERSE); solenoid.Toggle(); - EXPECT_EQ(DoubleSolenoid::kForward, solenoid.Get()); + EXPECT_EQ(DoubleSolenoid::FORWARD, solenoid.Get()); solenoid.Toggle(); - EXPECT_EQ(DoubleSolenoid::kReverse, solenoid.Get()); + EXPECT_EQ(DoubleSolenoid::REVERSE, solenoid.Get()); // Of shouldn't do anything on toggle - solenoid.Set(DoubleSolenoid::kOff); + solenoid.Set(DoubleSolenoid::OFF); solenoid.Toggle(); - EXPECT_EQ(DoubleSolenoid::kOff, solenoid.Get()); + EXPECT_EQ(DoubleSolenoid::OFF, solenoid.Get()); } TEST(DoubleSolenoidREVTest, InvalidForwardPort) { diff --git a/wpilibc/src/test/native/cpp/simulation/CTREPCMSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/CTREPCMSimTest.cpp index c61ba5556e..a54919004a 100644 --- a/wpilibc/src/test/native/cpp/simulation/CTREPCMSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/CTREPCMSimTest.cpp @@ -43,7 +43,7 @@ TEST(CTREPCMSimTest, SolenoidOutput) { callback3.Reset(); callback4.Reset(); - doubleSolenoid.Set(DoubleSolenoid::kReverse); + doubleSolenoid.Set(DoubleSolenoid::REVERSE); EXPECT_FALSE(callback3.WasTriggered()); EXPECT_FALSE(callback3.GetLastValue()); EXPECT_TRUE(callback4.WasTriggered()); @@ -55,7 +55,7 @@ TEST(CTREPCMSimTest, SolenoidOutput) { callback3.Reset(); callback4.Reset(); - doubleSolenoid.Set(DoubleSolenoid::kForward); + doubleSolenoid.Set(DoubleSolenoid::FORWARD); EXPECT_TRUE(callback3.WasTriggered()); EXPECT_TRUE(callback3.GetLastValue()); EXPECT_TRUE(callback4.WasTriggered()); @@ -67,7 +67,7 @@ TEST(CTREPCMSimTest, SolenoidOutput) { callback3.Reset(); callback4.Reset(); - doubleSolenoid.Set(DoubleSolenoid::kOff); + doubleSolenoid.Set(DoubleSolenoid::OFF); EXPECT_TRUE(callback3.WasTriggered()); EXPECT_FALSE(callback3.GetLastValue()); EXPECT_FALSE(callback4.WasTriggered()); diff --git a/wpilibc/src/test/native/cpp/simulation/REVPHSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/REVPHSimTest.cpp index 1e779b28d9..5548a80842 100644 --- a/wpilibc/src/test/native/cpp/simulation/REVPHSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/REVPHSimTest.cpp @@ -43,7 +43,7 @@ TEST(REVPHSimTest, SolenoidOutput) { callback3.Reset(); callback4.Reset(); - doubleSolenoid.Set(DoubleSolenoid::kReverse); + doubleSolenoid.Set(DoubleSolenoid::REVERSE); EXPECT_FALSE(callback3.WasTriggered()); EXPECT_FALSE(callback3.GetLastValue()); EXPECT_TRUE(callback4.WasTriggered()); @@ -55,7 +55,7 @@ TEST(REVPHSimTest, SolenoidOutput) { callback3.Reset(); callback4.Reset(); - doubleSolenoid.Set(DoubleSolenoid::kForward); + doubleSolenoid.Set(DoubleSolenoid::FORWARD); EXPECT_TRUE(callback3.WasTriggered()); EXPECT_TRUE(callback3.GetLastValue()); EXPECT_TRUE(callback4.WasTriggered()); @@ -67,7 +67,7 @@ TEST(REVPHSimTest, SolenoidOutput) { callback3.Reset(); callback4.Reset(); - doubleSolenoid.Set(DoubleSolenoid::kOff); + doubleSolenoid.Set(DoubleSolenoid::OFF); EXPECT_TRUE(callback3.WasTriggered()); EXPECT_FALSE(callback3.GetLastValue()); EXPECT_FALSE(callback4.WasTriggered()); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp index 6729b67527..85e64657f0 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp @@ -15,13 +15,13 @@ HatchSubsystem::HatchSubsystem() wpi::cmd::CommandPtr HatchSubsystem::GrabHatchCommand() { // implicitly require `this` return this->RunOnce( - [this] { m_hatchSolenoid.Set(wpi::DoubleSolenoid::kForward); }); + [this] { m_hatchSolenoid.Set(wpi::DoubleSolenoid::FORWARD); }); } wpi::cmd::CommandPtr HatchSubsystem::ReleaseHatchCommand() { // implicitly require `this` return this->RunOnce( - [this] { m_hatchSolenoid.Set(wpi::DoubleSolenoid::kReverse); }); + [this] { m_hatchSolenoid.Set(wpi::DoubleSolenoid::REVERSE); }); } void HatchSubsystem::InitSendable(wpi::util::SendableBuilder& builder) { @@ -30,6 +30,6 @@ void HatchSubsystem::InitSendable(wpi::util::SendableBuilder& builder) { // Publish the solenoid state to telemetry. builder.AddBooleanProperty( "extended", - [this] { return m_hatchSolenoid.Get() == wpi::DoubleSolenoid::kForward; }, + [this] { return m_hatchSolenoid.Get() == wpi::DoubleSolenoid::FORWARD; }, nullptr); } diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp index 335c01daf0..7dce9987fb 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp @@ -13,11 +13,11 @@ HatchSubsystem::HatchSubsystem() kHatchSolenoidPorts[0], kHatchSolenoidPorts[1]} {} void HatchSubsystem::GrabHatch() { - m_hatchSolenoid.Set(wpi::DoubleSolenoid::kForward); + m_hatchSolenoid.Set(wpi::DoubleSolenoid::FORWARD); } void HatchSubsystem::ReleaseHatch() { - m_hatchSolenoid.Set(wpi::DoubleSolenoid::kReverse); + m_hatchSolenoid.Set(wpi::DoubleSolenoid::REVERSE); } void HatchSubsystem::InitSendable(wpi::util::SendableBuilder& builder) { @@ -26,6 +26,6 @@ void HatchSubsystem::InitSendable(wpi::util::SendableBuilder& builder) { // Publish the solenoid state to telemetry. builder.AddBooleanProperty( "extended", - [this] { return m_hatchSolenoid.Get() == wpi::DoubleSolenoid::kForward; }, + [this] { return m_hatchSolenoid.Get() == wpi::DoubleSolenoid::FORWARD; }, nullptr); } diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp index d2c65a66cf..588cfc1321 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp @@ -5,7 +5,7 @@ #include "subsystems/Intake.hpp" wpi::cmd::CommandPtr Intake::IntakeCommand() { - return RunOnce([this] { m_piston.Set(wpi::DoubleSolenoid::kForward); }) + return RunOnce([this] { m_piston.Set(wpi::DoubleSolenoid::FORWARD); }) .AndThen(Run([this] { m_motor.SetDutyCycle(1.0); })) .WithName("Intake"); } @@ -13,7 +13,7 @@ wpi::cmd::CommandPtr Intake::IntakeCommand() { wpi::cmd::CommandPtr Intake::RetractCommand() { return RunOnce([this] { m_motor.Disable(); - m_piston.Set(wpi::DoubleSolenoid::kReverse); + m_piston.Set(wpi::DoubleSolenoid::REVERSE); }) .WithName("Retract"); } diff --git a/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp b/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp index 0957b0d6a0..9f1a690306 100644 --- a/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp +++ b/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp @@ -5,11 +5,11 @@ #include "subsystems/Intake.hpp" void Intake::Deploy() { - m_piston.Set(wpi::DoubleSolenoid::Value::kForward); + m_piston.Set(wpi::DoubleSolenoid::Value::FORWARD); } void Intake::Retract() { - m_piston.Set(wpi::DoubleSolenoid::Value::kReverse); + m_piston.Set(wpi::DoubleSolenoid::Value::REVERSE); m_motor.SetDutyCycle(0); // turn off the motor } @@ -22,5 +22,5 @@ void Intake::Activate(double velocity) { } bool Intake::IsDeployed() const { - return m_piston.Get() == wpi::DoubleSolenoid::Value::kForward; + return m_piston.Get() == wpi::DoubleSolenoid::Value::FORWARD; } diff --git a/wpilibcExamples/src/main/cpp/snippets/Solenoid/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/Solenoid/cpp/Robot.cpp index f08997f1fc..3c2c1e2d93 100644 --- a/wpilibcExamples/src/main/cpp/snippets/Solenoid/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/Solenoid/cpp/Robot.cpp @@ -45,9 +45,9 @@ void Robot::TeleopPeriodic() { * If a button is pressed, set the solenoid to the respective channel. */ if (m_stick.GetRawButtonPressed(kDoubleSolenoidForward)) { - m_doubleSolenoid.Set(wpi::DoubleSolenoid::kForward); + m_doubleSolenoid.Set(wpi::DoubleSolenoid::FORWARD); } else if (m_stick.GetRawButtonPressed(kDoubleSolenoidReverse)) { - m_doubleSolenoid.Set(wpi::DoubleSolenoid::kReverse); + m_doubleSolenoid.Set(wpi::DoubleSolenoid::REVERSE); } // On button press, toggle the compressor with the mode selected from the diff --git a/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp b/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp index 11570128fd..214d5ce1f2 100644 --- a/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp +++ b/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp @@ -38,10 +38,10 @@ TEST_F(IntakeTest, WorksWhenOpen) { TEST_F(IntakeTest, Retract) { intake.Retract(); - EXPECT_EQ(wpi::DoubleSolenoid::Value::kReverse, simPiston.Get()); + EXPECT_EQ(wpi::DoubleSolenoid::Value::REVERSE, simPiston.Get()); } TEST_F(IntakeTest, Deploy) { intake.Deploy(); - EXPECT_EQ(wpi::DoubleSolenoid::Value::kForward, simPiston.Get()); + EXPECT_EQ(wpi::DoubleSolenoid::Value::FORWARD, simPiston.Get()); } diff --git a/wpilibj/src/main/java/org/wpilib/hardware/pneumatic/DoubleSolenoid.java b/wpilibj/src/main/java/org/wpilib/hardware/pneumatic/DoubleSolenoid.java index 67c5a19b70..184a11c2d4 100644 --- a/wpilibj/src/main/java/org/wpilib/hardware/pneumatic/DoubleSolenoid.java +++ b/wpilibj/src/main/java/org/wpilib/hardware/pneumatic/DoubleSolenoid.java @@ -20,11 +20,11 @@ public class DoubleSolenoid implements Sendable, AutoCloseable { /** Possible values for a DoubleSolenoid. */ public enum Value { /** Off position. */ - kOff, + OFF, /** Forward position. */ - kForward, + FORWARD, /** Reverse position. */ - kReverse + REVERSE } private final int m_forwardMask; // The mask for the forward channel. @@ -134,9 +134,9 @@ public class DoubleSolenoid implements Sendable, AutoCloseable { public void set(final Value value) { int setValue = switch (value) { - case kOff -> 0; - case kForward -> m_forwardMask; - case kReverse -> m_reverseMask; + case OFF -> 0; + case FORWARD -> m_forwardMask; + case REVERSE -> m_reverseMask; }; m_module.setSolenoids(m_mask, setValue); @@ -151,11 +151,11 @@ public class DoubleSolenoid implements Sendable, AutoCloseable { int values = m_module.getSolenoids(); if ((values & m_forwardMask) != 0) { - return Value.kForward; + return Value.FORWARD; } else if ((values & m_reverseMask) != 0) { - return Value.kReverse; + return Value.REVERSE; } else { - return Value.kOff; + return Value.OFF; } } @@ -168,10 +168,10 @@ public class DoubleSolenoid implements Sendable, AutoCloseable { public void toggle() { Value value = get(); - if (value == Value.kForward) { - set(Value.kReverse); - } else if (value == Value.kReverse) { - set(Value.kForward); + if (value == Value.FORWARD) { + set(Value.REVERSE); + } else if (value == Value.REVERSE) { + set(Value.FORWARD); } } @@ -222,11 +222,11 @@ public class DoubleSolenoid implements Sendable, AutoCloseable { () -> get().name().substring(1), value -> { if ("Forward".equals(value)) { - set(Value.kForward); + set(Value.FORWARD); } else if ("Reverse".equals(value)) { - set(Value.kReverse); + set(Value.REVERSE); } else { - set(Value.kOff); + set(Value.OFF); } }); } diff --git a/wpilibj/src/main/java/org/wpilib/simulation/DoubleSolenoidSim.java b/wpilibj/src/main/java/org/wpilib/simulation/DoubleSolenoidSim.java index dd650d297b..3e3ab4b5a5 100644 --- a/wpilibj/src/main/java/org/wpilib/simulation/DoubleSolenoidSim.java +++ b/wpilibj/src/main/java/org/wpilib/simulation/DoubleSolenoidSim.java @@ -59,11 +59,11 @@ public class DoubleSolenoidSim { boolean fwdState = m_module.getSolenoidOutput(m_fwd); boolean revState = m_module.getSolenoidOutput(m_rev); if (fwdState && !revState) { - return DoubleSolenoid.Value.kForward; + return DoubleSolenoid.Value.FORWARD; } else if (!fwdState && revState) { - return DoubleSolenoid.Value.kReverse; + return DoubleSolenoid.Value.REVERSE; } else { - return DoubleSolenoid.Value.kOff; + return DoubleSolenoid.Value.OFF; } } @@ -73,8 +73,8 @@ public class DoubleSolenoidSim { * @param value The value to set (Off, Forward, Reverse) */ public void set(final DoubleSolenoid.Value value) { - m_module.setSolenoidOutput(m_fwd, value == DoubleSolenoid.Value.kForward); - m_module.setSolenoidOutput(m_rev, value == DoubleSolenoid.Value.kReverse); + m_module.setSolenoidOutput(m_fwd, value == DoubleSolenoid.Value.FORWARD); + m_module.setSolenoidOutput(m_rev, value == DoubleSolenoid.Value.REVERSE); } /** diff --git a/wpilibj/src/test/java/org/wpilib/hardware/pneumatic/DoubleSolenoidTestCTRE.java b/wpilibj/src/test/java/org/wpilib/hardware/pneumatic/DoubleSolenoidTestCTRE.java index fbe44358d8..898b6b7b27 100644 --- a/wpilibj/src/test/java/org/wpilib/hardware/pneumatic/DoubleSolenoidTestCTRE.java +++ b/wpilibj/src/test/java/org/wpilib/hardware/pneumatic/DoubleSolenoidTestCTRE.java @@ -14,14 +14,14 @@ class DoubleSolenoidTestCTRE { @Test void testValidInitialization() { try (DoubleSolenoid solenoid = new DoubleSolenoid(0, 3, PneumaticsModuleType.CTREPCM, 2, 3)) { - solenoid.set(DoubleSolenoid.Value.kReverse); - assertEquals(DoubleSolenoid.Value.kReverse, solenoid.get()); + solenoid.set(DoubleSolenoid.Value.REVERSE); + assertEquals(DoubleSolenoid.Value.REVERSE, solenoid.get()); - solenoid.set(DoubleSolenoid.Value.kForward); - assertEquals(DoubleSolenoid.Value.kForward, solenoid.get()); + solenoid.set(DoubleSolenoid.Value.FORWARD); + assertEquals(DoubleSolenoid.Value.FORWARD, solenoid.get()); - solenoid.set(DoubleSolenoid.Value.kOff); - assertEquals(DoubleSolenoid.Value.kOff, solenoid.get()); + solenoid.set(DoubleSolenoid.Value.OFF); + assertEquals(DoubleSolenoid.Value.OFF, solenoid.get()); } } @@ -63,18 +63,18 @@ class DoubleSolenoidTestCTRE { void testToggle() { try (DoubleSolenoid solenoid = new DoubleSolenoid(0, 4, PneumaticsModuleType.CTREPCM, 2, 3)) { // Bootstrap it into reverse - solenoid.set(DoubleSolenoid.Value.kReverse); + solenoid.set(DoubleSolenoid.Value.REVERSE); solenoid.toggle(); - assertEquals(DoubleSolenoid.Value.kForward, solenoid.get()); + assertEquals(DoubleSolenoid.Value.FORWARD, solenoid.get()); solenoid.toggle(); - assertEquals(DoubleSolenoid.Value.kReverse, solenoid.get()); + assertEquals(DoubleSolenoid.Value.REVERSE, solenoid.get()); // Of shouldn't do anything on toggle - solenoid.set(DoubleSolenoid.Value.kOff); + solenoid.set(DoubleSolenoid.Value.OFF); solenoid.toggle(); - assertEquals(DoubleSolenoid.Value.kOff, solenoid.get()); + assertEquals(DoubleSolenoid.Value.OFF, solenoid.get()); } } diff --git a/wpilibj/src/test/java/org/wpilib/hardware/pneumatic/DoubleSolenoidTestREV.java b/wpilibj/src/test/java/org/wpilib/hardware/pneumatic/DoubleSolenoidTestREV.java index 1bd5b382eb..e5d00caec2 100644 --- a/wpilibj/src/test/java/org/wpilib/hardware/pneumatic/DoubleSolenoidTestREV.java +++ b/wpilibj/src/test/java/org/wpilib/hardware/pneumatic/DoubleSolenoidTestREV.java @@ -14,14 +14,14 @@ class DoubleSolenoidTestREV { @Test void testValidInitialization() { try (DoubleSolenoid solenoid = new DoubleSolenoid(0, 3, PneumaticsModuleType.REVPH, 2, 3)) { - solenoid.set(DoubleSolenoid.Value.kReverse); - assertEquals(DoubleSolenoid.Value.kReverse, solenoid.get()); + solenoid.set(DoubleSolenoid.Value.REVERSE); + assertEquals(DoubleSolenoid.Value.REVERSE, solenoid.get()); - solenoid.set(DoubleSolenoid.Value.kForward); - assertEquals(DoubleSolenoid.Value.kForward, solenoid.get()); + solenoid.set(DoubleSolenoid.Value.FORWARD); + assertEquals(DoubleSolenoid.Value.FORWARD, solenoid.get()); - solenoid.set(DoubleSolenoid.Value.kOff); - assertEquals(DoubleSolenoid.Value.kOff, solenoid.get()); + solenoid.set(DoubleSolenoid.Value.OFF); + assertEquals(DoubleSolenoid.Value.OFF, solenoid.get()); } } @@ -63,18 +63,18 @@ class DoubleSolenoidTestREV { void testToggle() { try (DoubleSolenoid solenoid = new DoubleSolenoid(0, 4, PneumaticsModuleType.REVPH, 2, 3)) { // Bootstrap it into reverse - solenoid.set(DoubleSolenoid.Value.kReverse); + solenoid.set(DoubleSolenoid.Value.REVERSE); solenoid.toggle(); - assertEquals(DoubleSolenoid.Value.kForward, solenoid.get()); + assertEquals(DoubleSolenoid.Value.FORWARD, solenoid.get()); solenoid.toggle(); - assertEquals(DoubleSolenoid.Value.kReverse, solenoid.get()); + assertEquals(DoubleSolenoid.Value.REVERSE, solenoid.get()); // Of shouldn't do anything on toggle - solenoid.set(DoubleSolenoid.Value.kOff); + solenoid.set(DoubleSolenoid.Value.OFF); solenoid.toggle(); - assertEquals(DoubleSolenoid.Value.kOff, solenoid.get()); + assertEquals(DoubleSolenoid.Value.OFF, solenoid.get()); } } diff --git a/wpilibj/src/test/java/org/wpilib/simulation/CTREPCMSimTest.java b/wpilibj/src/test/java/org/wpilib/simulation/CTREPCMSimTest.java index 64f3fbbdcf..0571d50078 100644 --- a/wpilibj/src/test/java/org/wpilib/simulation/CTREPCMSimTest.java +++ b/wpilibj/src/test/java/org/wpilib/simulation/CTREPCMSimTest.java @@ -53,7 +53,7 @@ class CTREPCMSimTest { // Reverse callback3.reset(); callback4.reset(); - doubleSolenoid.set(DoubleSolenoid.Value.kReverse); + doubleSolenoid.set(DoubleSolenoid.Value.REVERSE); assertFalse(callback3.wasTriggered()); assertNull(callback3.getSetValue()); assertTrue(callback4.wasTriggered()); @@ -65,7 +65,7 @@ class CTREPCMSimTest { // Forward callback3.reset(); callback4.reset(); - doubleSolenoid.set(DoubleSolenoid.Value.kForward); + doubleSolenoid.set(DoubleSolenoid.Value.FORWARD); assertTrue(callback3.wasTriggered()); assertTrue(callback3.getSetValue()); assertTrue(callback4.wasTriggered()); @@ -77,7 +77,7 @@ class CTREPCMSimTest { // Off callback3.reset(); callback4.reset(); - doubleSolenoid.set(DoubleSolenoid.Value.kOff); + doubleSolenoid.set(DoubleSolenoid.Value.OFF); assertTrue(callback3.wasTriggered()); assertFalse(callback3.getSetValue()); assertFalse(callback4.wasTriggered()); diff --git a/wpilibj/src/test/java/org/wpilib/simulation/REVPHSimTest.java b/wpilibj/src/test/java/org/wpilib/simulation/REVPHSimTest.java index c7b27dd97a..de9dd34415 100644 --- a/wpilibj/src/test/java/org/wpilib/simulation/REVPHSimTest.java +++ b/wpilibj/src/test/java/org/wpilib/simulation/REVPHSimTest.java @@ -54,7 +54,7 @@ class REVPHSimTest { // Reverse callback3.reset(); callback4.reset(); - doubleSolenoid.set(DoubleSolenoid.Value.kReverse); + doubleSolenoid.set(DoubleSolenoid.Value.REVERSE); assertFalse(callback3.wasTriggered()); assertNull(callback3.getSetValue()); assertTrue(callback4.wasTriggered()); @@ -66,7 +66,7 @@ class REVPHSimTest { // Forward callback3.reset(); callback4.reset(); - doubleSolenoid.set(DoubleSolenoid.Value.kForward); + doubleSolenoid.set(DoubleSolenoid.Value.FORWARD); assertTrue(callback3.wasTriggered()); assertTrue(callback3.getSetValue()); assertTrue(callback4.wasTriggered()); @@ -78,7 +78,7 @@ class REVPHSimTest { // Off callback3.reset(); callback4.reset(); - doubleSolenoid.set(DoubleSolenoid.Value.kOff); + doubleSolenoid.set(DoubleSolenoid.Value.OFF); assertTrue(callback3.wasTriggered()); assertFalse(callback3.getSetValue()); assertFalse(callback4.wasTriggered()); diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/subsystems/HatchSubsystem.java b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/subsystems/HatchSubsystem.java index 72c71e563f..d5d0a39a2d 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/subsystems/HatchSubsystem.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/subsystems/HatchSubsystem.java @@ -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); } } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/subsystems/HatchSubsystem.java b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/subsystems/HatchSubsystem.java index de861faada..e422d78e83 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/subsystems/HatchSubsystem.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/subsystems/HatchSubsystem.java @@ -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); } } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Intake.java b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Intake.java index 09d79c500e..998d55a96d 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Intake.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Intake.java @@ -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"); } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/unittest/subsystems/Intake.java b/wpilibjExamples/src/main/java/org/wpilib/examples/unittest/subsystems/Intake.java index 993c3d0a61..4941b7e443 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/unittest/subsystems/Intake.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/unittest/subsystems/Intake.java @@ -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 diff --git a/wpilibjExamples/src/main/java/org/wpilib/snippets/solenoid/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/snippets/solenoid/Robot.java index 62563440c7..70ded4c656 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/snippets/solenoid/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/snippets/solenoid/Robot.java @@ -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. diff --git a/wpilibjExamples/src/test/java/org/wpilib/examples/unittest/subsystems/IntakeTest.java b/wpilibjExamples/src/test/java/org/wpilib/examples/unittest/subsystems/IntakeTest.java index 87fe151201..6b731fc91d 100644 --- a/wpilibjExamples/src/test/java/org/wpilib/examples/unittest/subsystems/IntakeTest.java +++ b/wpilibjExamples/src/test/java/org/wpilib/examples/unittest/subsystems/IntakeTest.java @@ -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()); } }