[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

@@ -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);
}
});
}

View File

@@ -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);
}
/**

View File

@@ -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());
}
}

View File

@@ -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());
}
}

View File

@@ -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());

View File

@@ -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());