From c69ef559ec7116d88fa6c5cfa206ec1d05e8259b Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Sat, 14 Sep 2024 10:54:47 -0400 Subject: [PATCH 01/15] first draft --- .../edu/wpi/first/wpilibj/DoubleSolenoid.java | 90 +++++++++++++++---- .../java/edu/wpi/first/wpilibj/Solenoid.java | 30 +++++++ .../wpilibj/simulation/DoubleSolenoidSim.java | 49 ++++++++++ .../first/wpilibj/simulation/SolenoidSim.java | 30 +++++++ 4 files changed, 182 insertions(+), 17 deletions(-) diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java index aab8b1e1060..49c101cbe7f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -12,10 +12,13 @@ import edu.wpi.first.util.sendable.SendableRegistry; /** - * DoubleSolenoid class for running 2 channels of high voltage Digital Output on the pneumatics + * DoubleSolenoid class for running 2 channels of high voltage Digital Output on + * the pneumatics * module. * - *

The DoubleSolenoid class is typically used for pneumatics solenoids that have two positions + *

+ * The DoubleSolenoid class is typically used for pneumatics solenoids that have + * two positions * controlled by two separate channels. */ public class DoubleSolenoid implements Sendable, AutoCloseable { @@ -39,7 +42,7 @@ public enum Value { /** * Constructs a double solenoid for a default module of a specific module type. * - * @param moduleType The module type to use. + * @param moduleType The module type to use. * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ @@ -49,14 +52,15 @@ public DoubleSolenoid( } /** - * Constructs a double solenoid for a specified module of a specific module type. + * Constructs a double solenoid for a specified module of a specific module + * type. * - * @param module The module of the solenoid module to use. - * @param moduleType The module type to use. + * @param module The module of the solenoid module to use. + * @param moduleType The module type to use. * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ - @SuppressWarnings({"PMD.UseTryWithResources", "this-escape"}) + @SuppressWarnings({ "PMD.UseTryWithResources", "this-escape" }) public DoubleSolenoid( final int module, final PneumaticsModuleType moduleType, @@ -125,12 +129,11 @@ public synchronized void close() { * @param value The value to set (Off, Forward, Reverse) */ public void set(final Value value) { - int setValue = - switch (value) { - case kOff -> 0; - case kForward -> m_forwardMask; - case kReverse -> m_reverseMask; - }; + int setValue = switch (value) { + case kOff -> 0; + case kForward -> m_forwardMask; + case kReverse -> m_reverseMask; + }; m_module.setSolenoids(m_mask, setValue); } @@ -152,11 +155,62 @@ public Value get() { } } + /** + * Returns true if the double solenoid is in a forward state. + * + * @return true if the double solenoid is in a forward state. + */ + public boolean isForward() { + return get() == Value.kForward; + } + + /** + * Returns true if the double solenoid is in a reverse state. + * + * @return true if the double solenoid is in a reverse state. + */ + public boolean isReverse() { + return get() == Value.kReverse; + } + + /** + * Returns true if the double solenoid is in an off state. + * + * @return true if the double solenoid in in an off state. + */ + public boolean isOff() { + return get() == Value.kOff; + } + + /** + * Sets the double solenoid to a forward state. + */ + public void forward() { + set(Value.kForward); + } + + /** + * Sets the double solenoid to a reverse state. + */ + public void reverse() { + set(Value.kReverse); + } + + /** + * Sets the double solenoid to a off state. + */ + public void off() { + set(Value.kOff); + } + /** * Toggle the value of the solenoid. * - *

If the solenoid is set to forward, it'll be set to reverse. If the solenoid is set to - * reverse, it'll be set to forward. If the solenoid is set to off, nothing happens. + *

+ * If the solenoid is set to forward, it'll be set to reverse. If the solenoid + * is set to + * reverse, it'll be set to forward. If the solenoid is set to off, nothing + * happens. */ public void toggle() { Value value = get(); @@ -187,7 +241,8 @@ public int getRevChannel() { } /** - * Check if the forward solenoid is Disabled. If a solenoid is shorted, it is added to the + * Check if the forward solenoid is Disabled. If a solenoid is shorted, it is + * added to the * DisabledList and disabled until power cycle, or until faults are cleared. * * @return If solenoid is disabled due to short. @@ -197,7 +252,8 @@ public boolean isFwdSolenoidDisabled() { } /** - * Check if the reverse solenoid is Disabled. If a solenoid is shorted, it is added to the + * Check if the reverse solenoid is Disabled. If a solenoid is shorted, it is + * added to the * DisabledList and disabled until power cycle, or until faults are cleared. * * @return If solenoid is disabled due to short. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index 9c516da72f2..13ce142316e 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -88,6 +88,36 @@ public boolean get() { return (currentAll & m_mask) != 0; } + /** + * Returns true if the solenoid is on. + * @return true if the solenoid is on. + */ + public boolean isOn(){ + return get() == true; + } + + /** + * Returns true if the solenoid is off. + * @return true if the solenoid off. + */ + public boolean isOff(){ + return get() == false; + } + + /** + * Turns the solenoid on. + */ + public void on(){ + set(true); + } + + /** + * Turns the solenoid off + */ + public void off(){ + set(false); + } + /** * Toggle the value of the solenoid. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java index baf3b0235bf..9fbb3ef417c 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java @@ -7,6 +7,7 @@ import edu.wpi.first.wpilibj.DoubleSolenoid; import edu.wpi.first.wpilibj.PneumaticsBase; import edu.wpi.first.wpilibj.PneumaticsModuleType; +import edu.wpi.first.wpilibj.DoubleSolenoid.Value; /** Class to control a simulated {@link edu.wpi.first.wpilibj.DoubleSolenoid}. */ public class DoubleSolenoidSim { @@ -67,6 +68,54 @@ public DoubleSolenoid.Value get() { } } + /** + * Returns true if the double solenoid is in a forward state. + * + * @return true if the double solenoid is in a forward state. + */ + public boolean isForward() { + return get() == Value.kForward; + } + + /** + * Returns true if the double solenoid is in a reverse state. + * + * @return true if the double solenoid is in a reverse state. + */ + public boolean isReverse() { + return get() == Value.kReverse; + } + + /** + * Returns true if the double solenoid is in an off state. + * + * @return true if the double solenoid in in an off state. + */ + public boolean isOff() { + return get() == Value.kOff; + } + + /** + * Sets the double solenoid to a forward state. + */ + public void forward() { + set(Value.kForward); + } + + /** + * Sets the double solenoid to a reverse state. + */ + public void reverse() { + set(Value.kReverse); + } + + /** + * Sets the double solenoid to a off state. + */ + public void off() { + set(Value.kOff); + } + /** * Set the value of the double solenoid output. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java index af767d211e2..719e9baabaa 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java @@ -54,6 +54,36 @@ public boolean getOutput() { return m_module.getSolenoidOutput(m_channel); } + /** + * Returns true if the solenoid is on. + * @return true if the solenoid is on. + */ + public boolean isOn(){ + return getOutput() == true; + } + + /** + * Returns true if the solenoid is off. + * @return true if the solenoid off. + */ + public boolean isOff(){ + return getOutput() == false; + } + + /** + * Turns the solenoid on. + */ + public void on(){ + setOutput(true); + } + + /** + * Turns the solenoid off + */ + public void off(){ + setOutput(false); + } + /** * Change the solenoid output. * From 54baa1d0da10df6db3df92a72fd246ea65e339d1 Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Sat, 14 Sep 2024 11:16:09 -0400 Subject: [PATCH 02/15] added C++ --- .../src/main/native/cpp/DoubleSolenoid.cpp | 24 +++++++++++++ wpilibc/src/main/native/cpp/Solenoid.cpp | 16 +++++++++ .../cpp/simulation/DoubleSolenoidSim.cpp | 24 +++++++++++++ .../native/cpp/simulation/SolenoidSim.cpp | 16 +++++++++ .../main/native/include/frc/DoubleSolenoid.h | 34 +++++++++++++++++++ .../src/main/native/include/frc/Solenoid.h | 26 ++++++++++++++ .../frc/simulation/DoubleSolenoidSim.h | 33 ++++++++++++++++++ .../include/frc/simulation/SolenoidSim.h | 26 ++++++++++++++ 8 files changed, 199 insertions(+) diff --git a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp index c111622545c..bc0a9292f9e 100644 --- a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp +++ b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp @@ -110,6 +110,30 @@ void DoubleSolenoid::Toggle() { } } +bool DoubleSolenoid::IsForward() const { + return Get() == kForward; +} + +bool DoubleSolenoid::IsReverse() const { + return Get() == kReverse; +} + +bool DoubleSolenoid::IsOff() const { + return Get() == kOff; +} + +void DoubleSolenoid::Forward() { + Set(kForward); +} + +void DoubleSolenoid::Reverse() { + Set(kReverse); +} + +void DoubleSolenoid::Off() { + Set(kOff); +} + int DoubleSolenoid::GetFwdChannel() const { return m_forwardChannel; } diff --git a/wpilibc/src/main/native/cpp/Solenoid.cpp b/wpilibc/src/main/native/cpp/Solenoid.cpp index 819f79a8d71..1a8061fab32 100644 --- a/wpilibc/src/main/native/cpp/Solenoid.cpp +++ b/wpilibc/src/main/native/cpp/Solenoid.cpp @@ -54,6 +54,22 @@ bool Solenoid::Get() const { return (currentAll & m_mask) != 0; } +bool Solenoid::IsOn() const { + return Get() == true; +} + +bool Solenoid::IsOff() const { + return Get() == false; +} + +void Solenoid::On() { + Set(true); +} + +void Solenoid::Off() { + Set(false); +} + void Solenoid::Toggle() { Set(!Get()); } diff --git a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp index da99867b2e4..a318acf6aa1 100644 --- a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp @@ -43,6 +43,30 @@ void DoubleSolenoidSim::Set(DoubleSolenoid::Value output) { m_module->SetSolenoidOutput(m_rev, output == DoubleSolenoid::Value::kReverse); } +bool DoubleSolenoid::IsForward() const { + return Get() == kForward; +} + +bool DoubleSolenoid::IsReverse() const { + return Get() == kReverse; +} + +bool DoubleSolenoid::IsOff() const { + return Get() == kOff; +} + +void DoubleSolenoid::Forward() { + Set(kForward); +} + +void DoubleSolenoid::Reverse() { + Set(kReverse); +} + +void DoubleSolenoid::Off() { + Set(kOff); +} + std::shared_ptr DoubleSolenoidSim::GetModuleSim() const { return m_module; } diff --git a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp index 29d820783e5..67874bb9b31 100644 --- a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp @@ -30,6 +30,22 @@ void SolenoidSim::SetOutput(bool output) { m_module->SetSolenoidOutput(m_channel, output); } +bool SolenoidSim::IsOn() const { + return GetOutput() == true; +} + +bool SolenoidSim::IsOff() const { + return GetOutput() == false; +} + +void SolenoidSim::On() { + SetOutput(true); +} + +void SolenoidSim::Off() { + SetOutput(false); +} + std::unique_ptr SolenoidSim::RegisterOutputCallback( NotifyCallback callback, bool initialNotify) { return m_module->RegisterSolenoidOutputCallback(m_channel, callback, diff --git a/wpilibc/src/main/native/include/frc/DoubleSolenoid.h b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h index 57c2c11d82a..ac67a67e441 100644 --- a/wpilibc/src/main/native/include/frc/DoubleSolenoid.h +++ b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h @@ -88,6 +88,40 @@ class DoubleSolenoid : public wpi::Sendable, */ void Toggle(); + /** + * Returns true if the double solenoid is in a forward state. + * @return true if the double solenoid is in a forward state. + */ + virtual bool IsForward() const; + + /** + * Returns true if the double solenoid is in a reverse state. + * @return true if the double solenoid is in a reverse state. + */ + virtual bool IsReverse() const; + + /** + * Returns true if the double solenoid is in an off state. + * @return true if the double solenoid is in an off state. + */ + virtual bool IsOff() const; + + /** + * Sets the double solenoid to a forward state + */ + virtual void Forward(); + + /** + * Sets the double solenoid to a reverse state + */ + virtual void Reverse(); + + /** + * Sets the double solenoid to an off state + */ + virtual void Off(); + + /** * Get the forward channel. * diff --git a/wpilibc/src/main/native/include/frc/Solenoid.h b/wpilibc/src/main/native/include/frc/Solenoid.h index 7fa49530a17..deaf1f185d1 100644 --- a/wpilibc/src/main/native/include/frc/Solenoid.h +++ b/wpilibc/src/main/native/include/frc/Solenoid.h @@ -61,6 +61,32 @@ class Solenoid : public wpi::Sendable, public wpi::SendableHelper { */ virtual bool Get() const; + /** + * Returns true if the solenoid is on. + * + * @return true if the solenoid is on. + * + */ + virtual bool IsOn() const; + + /** + * Returns true if the solenoid is off. + * + * @return true if the solenoid is off. + * + */ + virtual bool IsOff() const; + + /** + * Turns the solenoid on. + */ + virtual void On(); + + /** + * Turns the solenoid off. + */ + virtual void Off(); + /** * Toggle the value of the solenoid. * diff --git a/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h b/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h index eaa697f679d..ce4c79efa18 100644 --- a/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h @@ -22,6 +22,39 @@ class DoubleSolenoidSim { DoubleSolenoid::Value Get() const; void Set(DoubleSolenoid::Value output); + /** + * Returns true if the double solenoid is in a forward state. + * @return true if the double solenoid is in a forward state. + */ + virtual bool IsForward() const; + + /** + * Returns true if the double solenoid is in a reverse state. + * @return true if the double solenoid is in a reverse state. + */ + virtual bool IsReverse() const; + + /** + * Returns true if the double solenoid is in an off state. + * @return true if the double solenoid is in an off state. + */ + virtual bool IsOff() const; + + /** + * Sets the double solenoid to a forward state + */ + virtual void Forward(); + + /** + * Sets the double solenoid to a reverse state + */ + virtual void Reverse(); + + /** + * Sets the double solenoid to an off state + */ + virtual void Off(); + std::shared_ptr GetModuleSim() const; private: diff --git a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h index dd2e8e79cc1..2d5aa5792f6 100644 --- a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h @@ -21,6 +21,32 @@ class SolenoidSim { bool GetOutput() const; void SetOutput(bool output); + /** + * Returns true if the solenoid is on. + * + * @return true if the solenoid is on. + * + */ + virtual bool IsOn() const; + + /** + * Returns true if the solenoid is off. + * + * @return true if the solenoid is off. + * + */ + virtual bool IsOff() const; + + /** + * Turns the solenoid on. + */ + virtual void On(); + + /** + * Turns the solenoid off. + */ + virtual void Off(); + /** * Register a callback to be run when the output of this solenoid has changed. * From 4bb29b2e4817d72b3d1d500e0199854838cf95df Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 14 Sep 2024 15:27:35 +0000 Subject: [PATCH 03/15] Formatting fixes --- .../main/native/include/frc/DoubleSolenoid.h | 15 +++-- .../src/main/native/include/frc/Solenoid.h | 6 +- .../frc/simulation/DoubleSolenoidSim.h | 14 ++--- .../include/frc/simulation/SolenoidSim.h | 8 +-- .../edu/wpi/first/wpilibj/DoubleSolenoid.java | 60 +++++++------------ .../java/edu/wpi/first/wpilibj/Solenoid.java | 20 +++---- .../wpilibj/simulation/DoubleSolenoidSim.java | 22 +++---- .../first/wpilibj/simulation/SolenoidSim.java | 24 ++++---- 8 files changed, 72 insertions(+), 97 deletions(-) diff --git a/wpilibc/src/main/native/include/frc/DoubleSolenoid.h b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h index ac67a67e441..05aac59681d 100644 --- a/wpilibc/src/main/native/include/frc/DoubleSolenoid.h +++ b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h @@ -90,37 +90,36 @@ class DoubleSolenoid : public wpi::Sendable, /** * Returns true if the double solenoid is in a forward state. - * @return true if the double solenoid is in a forward state. + * @return true if the double solenoid is in a forward state. */ virtual bool IsForward() const; /** * Returns true if the double solenoid is in a reverse state. - * @return true if the double solenoid is in a reverse state. + * @return true if the double solenoid is in a reverse state. */ virtual bool IsReverse() const; /** * Returns true if the double solenoid is in an off state. - * @return true if the double solenoid is in an off state. + * @return true if the double solenoid is in an off state. */ - virtual bool IsOff() const; + virtual bool IsOff() const; /** * Sets the double solenoid to a forward state */ - virtual void Forward(); + virtual void Forward(); /** * Sets the double solenoid to a reverse state */ - virtual void Reverse(); + virtual void Reverse(); /** * Sets the double solenoid to an off state */ - virtual void Off(); - + virtual void Off(); /** * Get the forward channel. diff --git a/wpilibc/src/main/native/include/frc/Solenoid.h b/wpilibc/src/main/native/include/frc/Solenoid.h index deaf1f185d1..dcce80de108 100644 --- a/wpilibc/src/main/native/include/frc/Solenoid.h +++ b/wpilibc/src/main/native/include/frc/Solenoid.h @@ -78,12 +78,12 @@ class Solenoid : public wpi::Sendable, public wpi::SendableHelper { virtual bool IsOff() const; /** - * Turns the solenoid on. + * Turns the solenoid on. */ virtual void On(); - + /** - * Turns the solenoid off. + * Turns the solenoid off. */ virtual void Off(); diff --git a/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h b/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h index ce4c79efa18..36f26c818a1 100644 --- a/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h @@ -24,36 +24,36 @@ class DoubleSolenoidSim { /** * Returns true if the double solenoid is in a forward state. - * @return true if the double solenoid is in a forward state. + * @return true if the double solenoid is in a forward state. */ virtual bool IsForward() const; /** * Returns true if the double solenoid is in a reverse state. - * @return true if the double solenoid is in a reverse state. + * @return true if the double solenoid is in a reverse state. */ virtual bool IsReverse() const; /** * Returns true if the double solenoid is in an off state. - * @return true if the double solenoid is in an off state. + * @return true if the double solenoid is in an off state. */ - virtual bool IsOff() const; + virtual bool IsOff() const; /** * Sets the double solenoid to a forward state */ - virtual void Forward(); + virtual void Forward(); /** * Sets the double solenoid to a reverse state */ - virtual void Reverse(); + virtual void Reverse(); /** * Sets the double solenoid to an off state */ - virtual void Off(); + virtual void Off(); std::shared_ptr GetModuleSim() const; diff --git a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h index 2d5aa5792f6..f5c99e53385 100644 --- a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h @@ -38,14 +38,14 @@ class SolenoidSim { virtual bool IsOff() const; /** - * Turns the solenoid on. + * Turns the solenoid on. */ virtual void On(); - + /** - * Turns the solenoid off. + * Turns the solenoid off. */ - virtual void Off(); + virtual void Off(); /** * Register a callback to be run when the output of this solenoid has changed. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java index 49c101cbe7f..618a97b5fcb 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -12,13 +12,10 @@ import edu.wpi.first.util.sendable.SendableRegistry; /** - * DoubleSolenoid class for running 2 channels of high voltage Digital Output on - * the pneumatics + * DoubleSolenoid class for running 2 channels of high voltage Digital Output on the pneumatics * module. * - *

- * The DoubleSolenoid class is typically used for pneumatics solenoids that have - * two positions + *

The DoubleSolenoid class is typically used for pneumatics solenoids that have two positions * controlled by two separate channels. */ public class DoubleSolenoid implements Sendable, AutoCloseable { @@ -42,7 +39,7 @@ public enum Value { /** * Constructs a double solenoid for a default module of a specific module type. * - * @param moduleType The module type to use. + * @param moduleType The module type to use. * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ @@ -52,15 +49,14 @@ public DoubleSolenoid( } /** - * Constructs a double solenoid for a specified module of a specific module - * type. + * Constructs a double solenoid for a specified module of a specific module type. * - * @param module The module of the solenoid module to use. - * @param moduleType The module type to use. + * @param module The module of the solenoid module to use. + * @param moduleType The module type to use. * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ - @SuppressWarnings({ "PMD.UseTryWithResources", "this-escape" }) + @SuppressWarnings({"PMD.UseTryWithResources", "this-escape"}) public DoubleSolenoid( final int module, final PneumaticsModuleType moduleType, @@ -129,11 +125,12 @@ public synchronized void close() { * @param value The value to set (Off, Forward, Reverse) */ public void set(final Value value) { - int setValue = switch (value) { - case kOff -> 0; - case kForward -> m_forwardMask; - case kReverse -> m_reverseMask; - }; + int setValue = + switch (value) { + case kOff -> 0; + case kForward -> m_forwardMask; + case kReverse -> m_reverseMask; + }; m_module.setSolenoids(m_mask, setValue); } @@ -157,7 +154,7 @@ public Value get() { /** * Returns true if the double solenoid is in a forward state. - * + * * @return true if the double solenoid is in a forward state. */ public boolean isForward() { @@ -166,7 +163,7 @@ public boolean isForward() { /** * Returns true if the double solenoid is in a reverse state. - * + * * @return true if the double solenoid is in a reverse state. */ public boolean isReverse() { @@ -175,30 +172,24 @@ public boolean isReverse() { /** * Returns true if the double solenoid is in an off state. - * + * * @return true if the double solenoid in in an off state. */ public boolean isOff() { return get() == Value.kOff; } - /** - * Sets the double solenoid to a forward state. - */ + /** Sets the double solenoid to a forward state. */ public void forward() { set(Value.kForward); } - /** - * Sets the double solenoid to a reverse state. - */ + /** Sets the double solenoid to a reverse state. */ public void reverse() { set(Value.kReverse); } - /** - * Sets the double solenoid to a off state. - */ + /** Sets the double solenoid to a off state. */ public void off() { set(Value.kOff); } @@ -206,11 +197,8 @@ public void off() { /** * Toggle the value of the solenoid. * - *

- * If the solenoid is set to forward, it'll be set to reverse. If the solenoid - * is set to - * reverse, it'll be set to forward. If the solenoid is set to off, nothing - * happens. + *

If the solenoid is set to forward, it'll be set to reverse. If the solenoid is set to + * reverse, it'll be set to forward. If the solenoid is set to off, nothing happens. */ public void toggle() { Value value = get(); @@ -241,8 +229,7 @@ public int getRevChannel() { } /** - * Check if the forward solenoid is Disabled. If a solenoid is shorted, it is - * added to the + * Check if the forward solenoid is Disabled. If a solenoid is shorted, it is added to the * DisabledList and disabled until power cycle, or until faults are cleared. * * @return If solenoid is disabled due to short. @@ -252,8 +239,7 @@ public boolean isFwdSolenoidDisabled() { } /** - * Check if the reverse solenoid is Disabled. If a solenoid is shorted, it is - * added to the + * Check if the reverse solenoid is Disabled. If a solenoid is shorted, it is added to the * DisabledList and disabled until power cycle, or until faults are cleared. * * @return If solenoid is disabled due to short. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index 13ce142316e..4d5e2770a47 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -90,31 +90,29 @@ public boolean get() { /** * Returns true if the solenoid is on. - * @return true if the solenoid is on. + * + * @return true if the solenoid is on. */ - public boolean isOn(){ + public boolean isOn() { return get() == true; } /** * Returns true if the solenoid is off. + * * @return true if the solenoid off. */ - public boolean isOff(){ + public boolean isOff() { return get() == false; } - /** - * Turns the solenoid on. - */ - public void on(){ + /** Turns the solenoid on. */ + public void on() { set(true); } - /** - * Turns the solenoid off - */ - public void off(){ + /** Turns the solenoid off */ + public void off() { set(false); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java index 9fbb3ef417c..790aa85dfc9 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java @@ -5,9 +5,9 @@ package edu.wpi.first.wpilibj.simulation; import edu.wpi.first.wpilibj.DoubleSolenoid; +import edu.wpi.first.wpilibj.DoubleSolenoid.Value; import edu.wpi.first.wpilibj.PneumaticsBase; import edu.wpi.first.wpilibj.PneumaticsModuleType; -import edu.wpi.first.wpilibj.DoubleSolenoid.Value; /** Class to control a simulated {@link edu.wpi.first.wpilibj.DoubleSolenoid}. */ public class DoubleSolenoidSim { @@ -70,7 +70,7 @@ public DoubleSolenoid.Value get() { /** * Returns true if the double solenoid is in a forward state. - * + * * @return true if the double solenoid is in a forward state. */ public boolean isForward() { @@ -79,7 +79,7 @@ public boolean isForward() { /** * Returns true if the double solenoid is in a reverse state. - * + * * @return true if the double solenoid is in a reverse state. */ public boolean isReverse() { @@ -88,33 +88,27 @@ public boolean isReverse() { /** * Returns true if the double solenoid is in an off state. - * + * * @return true if the double solenoid in in an off state. */ public boolean isOff() { return get() == Value.kOff; } - /** - * Sets the double solenoid to a forward state. - */ + /** Sets the double solenoid to a forward state. */ public void forward() { set(Value.kForward); } - /** - * Sets the double solenoid to a reverse state. - */ + /** Sets the double solenoid to a reverse state. */ public void reverse() { set(Value.kReverse); } - /** - * Sets the double solenoid to a off state. - */ + /** Sets the double solenoid to a off state. */ public void off() { set(Value.kOff); - } + } /** * Set the value of the double solenoid output. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java index 719e9baabaa..7a5cec04a98 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java @@ -56,33 +56,31 @@ public boolean getOutput() { /** * Returns true if the solenoid is on. - * @return true if the solenoid is on. + * + * @return true if the solenoid is on. */ - public boolean isOn(){ + public boolean isOn() { return getOutput() == true; } /** * Returns true if the solenoid is off. + * * @return true if the solenoid off. */ - public boolean isOff(){ + public boolean isOff() { return getOutput() == false; - } + } - /** - * Turns the solenoid on. - */ - public void on(){ + /** Turns the solenoid on. */ + public void on() { setOutput(true); } - /** - * Turns the solenoid off - */ - public void off(){ + /** Turns the solenoid off */ + public void off() { setOutput(false); - } + } /** * Change the solenoid output. From 99398fd9800c7c46b403e579d89c53abd095e380 Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Sat, 14 Sep 2024 12:25:37 -0400 Subject: [PATCH 04/15] changes made as instructed. --- wpilibc/src/main/native/cpp/DoubleSolenoid.cpp | 12 ++++++------ wpilibc/src/main/native/cpp/Solenoid.cpp | 4 ++-- .../native/cpp/simulation/DoubleSolenoidSim.cpp | 12 ++++++------ .../main/native/cpp/simulation/SolenoidSim.cpp | 8 ++++---- .../src/main/native/include/frc/DoubleSolenoid.h | 16 ++++++++-------- wpilibc/src/main/native/include/frc/Solenoid.h | 12 ++++++------ .../include/frc/simulation/DoubleSolenoidSim.h | 12 ++++++------ .../native/include/frc/simulation/SolenoidSim.h | 8 ++++---- .../edu/wpi/first/wpilibj/DoubleSolenoid.java | 6 +++--- .../java/edu/wpi/first/wpilibj/Solenoid.java | 4 ++-- .../wpilibj/simulation/DoubleSolenoidSim.java | 6 +++--- .../first/wpilibj/simulation/SolenoidSim.java | 16 ++++++++-------- 12 files changed, 58 insertions(+), 58 deletions(-) diff --git a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp index bc0a9292f9e..3b9b998d7ff 100644 --- a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp +++ b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp @@ -110,27 +110,27 @@ void DoubleSolenoid::Toggle() { } } -bool DoubleSolenoid::IsForward() const { +bool DoubleSolenoid::IsForward() { return Get() == kForward; } -bool DoubleSolenoid::IsReverse() const { +bool DoubleSolenoid::IsReverse() { return Get() == kReverse; } -bool DoubleSolenoid::IsOff() const { +bool DoubleSolenoid::IsOff() { return Get() == kOff; } -void DoubleSolenoid::Forward() { +void DoubleSolenoid::SetForward() { Set(kForward); } -void DoubleSolenoid::Reverse() { +void DoubleSolenoid::SetReverse() { Set(kReverse); } -void DoubleSolenoid::Off() { +void DoubleSolenoid::SetOff() { Set(kOff); } diff --git a/wpilibc/src/main/native/cpp/Solenoid.cpp b/wpilibc/src/main/native/cpp/Solenoid.cpp index 1a8061fab32..85bf2bfcd56 100644 --- a/wpilibc/src/main/native/cpp/Solenoid.cpp +++ b/wpilibc/src/main/native/cpp/Solenoid.cpp @@ -62,11 +62,11 @@ bool Solenoid::IsOff() const { return Get() == false; } -void Solenoid::On() { +void Solenoid::SetOn() { Set(true); } -void Solenoid::Off() { +void Solenoid::SetOff() { Set(false); } diff --git a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp index a318acf6aa1..a7d6a781ba4 100644 --- a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp @@ -43,27 +43,27 @@ void DoubleSolenoidSim::Set(DoubleSolenoid::Value output) { m_module->SetSolenoidOutput(m_rev, output == DoubleSolenoid::Value::kReverse); } -bool DoubleSolenoid::IsForward() const { +bool DoubleSolenoid::IsForward() { return Get() == kForward; } -bool DoubleSolenoid::IsReverse() const { +bool DoubleSolenoid::IsReverse() { return Get() == kReverse; } -bool DoubleSolenoid::IsOff() const { +bool DoubleSolenoid::IsOff() { return Get() == kOff; } -void DoubleSolenoid::Forward() { +void DoubleSolenoid::SetForward() { Set(kForward); } -void DoubleSolenoid::Reverse() { +void DoubleSolenoid::SetReverse() { Set(kReverse); } -void DoubleSolenoid::Off() { +void DoubleSolenoid::SetOff() { Set(kOff); } diff --git a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp index 67874bb9b31..b0ff903a4df 100644 --- a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp @@ -30,19 +30,19 @@ void SolenoidSim::SetOutput(bool output) { m_module->SetSolenoidOutput(m_channel, output); } -bool SolenoidSim::IsOn() const { +bool SolenoidSim::IsOn() { return GetOutput() == true; } -bool SolenoidSim::IsOff() const { +bool SolenoidSim::IsOff() { return GetOutput() == false; } -void SolenoidSim::On() { +void SolenoidSim::SetOn() { SetOutput(true); } -void SolenoidSim::Off() { +void SolenoidSim::SetOff() { SetOutput(false); } diff --git a/wpilibc/src/main/native/include/frc/DoubleSolenoid.h b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h index 05aac59681d..3c24c80f3dc 100644 --- a/wpilibc/src/main/native/include/frc/DoubleSolenoid.h +++ b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h @@ -70,14 +70,14 @@ class DoubleSolenoid : public wpi::Sendable, * * @param value The value to set (Off, Forward or Reverse) */ - virtual void Set(Value value); + void Set(Value value); /** * Read the current value of the solenoid. * * @return The current value of the solenoid. */ - virtual Value Get() const; + Value Get() const; /** * Toggle the value of the solenoid. @@ -92,34 +92,34 @@ class DoubleSolenoid : public wpi::Sendable, * Returns true if the double solenoid is in a forward state. * @return true if the double solenoid is in a forward state. */ - virtual bool IsForward() const; + bool IsForward(); /** * Returns true if the double solenoid is in a reverse state. * @return true if the double solenoid is in a reverse state. */ - virtual bool IsReverse() const; + bool IsReverse(); /** * Returns true if the double solenoid is in an off state. * @return true if the double solenoid is in an off state. */ - virtual bool IsOff() const; + bool IsOff(); /** * Sets the double solenoid to a forward state */ - virtual void Forward(); + void SetForward(); /** * Sets the double solenoid to a reverse state */ - virtual void Reverse(); + void SetReverse(); /** * Sets the double solenoid to an off state */ - virtual void Off(); + void SetOff(); /** * Get the forward channel. diff --git a/wpilibc/src/main/native/include/frc/Solenoid.h b/wpilibc/src/main/native/include/frc/Solenoid.h index dcce80de108..d00452013d1 100644 --- a/wpilibc/src/main/native/include/frc/Solenoid.h +++ b/wpilibc/src/main/native/include/frc/Solenoid.h @@ -52,14 +52,14 @@ class Solenoid : public wpi::Sendable, public wpi::SendableHelper { * * @param on Turn the solenoid output off or on. */ - virtual void Set(bool on); + void Set(bool on); /** * Read the current value of the solenoid. * * @return The current value of the solenoid. */ - virtual bool Get() const; + bool Get() const; /** * Returns true if the solenoid is on. @@ -67,7 +67,7 @@ class Solenoid : public wpi::Sendable, public wpi::SendableHelper { * @return true if the solenoid is on. * */ - virtual bool IsOn() const; + bool IsOn() const; /** * Returns true if the solenoid is off. @@ -75,17 +75,17 @@ class Solenoid : public wpi::Sendable, public wpi::SendableHelper { * @return true if the solenoid is off. * */ - virtual bool IsOff() const; + bool IsOff() const; /** * Turns the solenoid on. */ - virtual void On(); + void SetOn(); /** * Turns the solenoid off. */ - virtual void Off(); + void SetOff(); /** * Toggle the value of the solenoid. diff --git a/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h b/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h index 36f26c818a1..a62a0ecb852 100644 --- a/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/DoubleSolenoidSim.h @@ -26,34 +26,34 @@ class DoubleSolenoidSim { * Returns true if the double solenoid is in a forward state. * @return true if the double solenoid is in a forward state. */ - virtual bool IsForward() const; + bool IsForward(); /** * Returns true if the double solenoid is in a reverse state. * @return true if the double solenoid is in a reverse state. */ - virtual bool IsReverse() const; + bool IsReverse(); /** * Returns true if the double solenoid is in an off state. * @return true if the double solenoid is in an off state. */ - virtual bool IsOff() const; + bool IsOff(); /** * Sets the double solenoid to a forward state */ - virtual void Forward(); + void SetForward(); /** * Sets the double solenoid to a reverse state */ - virtual void Reverse(); + void SetReverse(); /** * Sets the double solenoid to an off state */ - virtual void Off(); + void SetOff(); std::shared_ptr GetModuleSim() const; diff --git a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h index f5c99e53385..dbd8c4f0de5 100644 --- a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h @@ -27,7 +27,7 @@ class SolenoidSim { * @return true if the solenoid is on. * */ - virtual bool IsOn() const; + bool IsOn(); /** * Returns true if the solenoid is off. @@ -35,17 +35,17 @@ class SolenoidSim { * @return true if the solenoid is off. * */ - virtual bool IsOff() const; + bool IsOff(); /** * Turns the solenoid on. */ - virtual void On(); + void SetOn(); /** * Turns the solenoid off. */ - virtual void Off(); + void SetOff(); /** * Register a callback to be run when the output of this solenoid has changed. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java index 618a97b5fcb..c06ff94cf7e 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -180,17 +180,17 @@ public boolean isOff() { } /** Sets the double solenoid to a forward state. */ - public void forward() { + public void setForward() { set(Value.kForward); } /** Sets the double solenoid to a reverse state. */ - public void reverse() { + public void setReverse() { set(Value.kReverse); } /** Sets the double solenoid to a off state. */ - public void off() { + public void setOff() { set(Value.kOff); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index 4d5e2770a47..399e7491be6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -107,12 +107,12 @@ public boolean isOff() { } /** Turns the solenoid on. */ - public void on() { + public void setOn() { set(true); } /** Turns the solenoid off */ - public void off() { + public void setOff() { set(false); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java index 790aa85dfc9..c2238fbf5be 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DoubleSolenoidSim.java @@ -96,17 +96,17 @@ public boolean isOff() { } /** Sets the double solenoid to a forward state. */ - public void forward() { + public void setForward() { set(Value.kForward); } /** Sets the double solenoid to a reverse state. */ - public void reverse() { + public void setReverse() { set(Value.kReverse); } /** Sets the double solenoid to a off state. */ - public void off() { + public void setOff() { set(Value.kOff); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java index 7a5cec04a98..04b382c61d3 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java @@ -50,7 +50,7 @@ public SolenoidSim(PneumaticsModuleType moduleType, int channel) { * * @return the solenoid output */ - public boolean getOutput() { + public boolean get() { return m_module.getSolenoidOutput(m_channel); } @@ -60,7 +60,7 @@ public boolean getOutput() { * @return true if the solenoid is on. */ public boolean isOn() { - return getOutput() == true; + return get() == true; } /** @@ -69,17 +69,17 @@ public boolean isOn() { * @return true if the solenoid off. */ public boolean isOff() { - return getOutput() == false; + return get() == false; } /** Turns the solenoid on. */ - public void on() { - setOutput(true); + public void setOn() { + set(true); } /** Turns the solenoid off */ - public void off() { - setOutput(false); + public void setOff() { + set(false); } /** @@ -87,7 +87,7 @@ public void off() { * * @param output the new solenoid output */ - public void setOutput(boolean output) { + public void set(boolean output) { m_module.setSolenoidOutput(m_channel, output); } From 8be079522fec9adb668b565da0f9c1727974fd4a Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Sat, 14 Sep 2024 12:29:04 -0400 Subject: [PATCH 05/15] type fix --- .../main/native/cpp/simulation/DoubleSolenoidSim.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp index a7d6a781ba4..74b33ebd4f2 100644 --- a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp @@ -43,27 +43,27 @@ void DoubleSolenoidSim::Set(DoubleSolenoid::Value output) { m_module->SetSolenoidOutput(m_rev, output == DoubleSolenoid::Value::kReverse); } -bool DoubleSolenoid::IsForward() { +bool DoubleSolenoidSim::IsForward() { return Get() == kForward; } -bool DoubleSolenoid::IsReverse() { +bool DoubleSolenoidSim::IsReverse() { return Get() == kReverse; } -bool DoubleSolenoid::IsOff() { +bool DoubleSolenoidSim::IsOff() { return Get() == kOff; } -void DoubleSolenoid::SetForward() { +void DoubleSolenoidSim::SetForward() { Set(kForward); } -void DoubleSolenoid::SetReverse() { +void DoubleSolenoidSim::SetReverse() { Set(kReverse); } -void DoubleSolenoid::SetOff() { +void DoubleSolenoidSim::SetOff() { Set(kOff); } From ccc5a81152da3668e92c5792169afce41e81b98c Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Sat, 14 Sep 2024 12:32:04 -0400 Subject: [PATCH 06/15] fixed enums --- .../native/cpp/simulation/DoubleSolenoidSim.cpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp index 74b33ebd4f2..cbdaf89e4b1 100644 --- a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp @@ -3,6 +3,7 @@ // the WPILib BSD license file in the root directory of this project. #include "frc/simulation/DoubleSolenoidSim.h" +#include "frc/DoubleSolenoid.h" #include "frc/PneumaticsBase.h" @@ -44,27 +45,27 @@ void DoubleSolenoidSim::Set(DoubleSolenoid::Value output) { } bool DoubleSolenoidSim::IsForward() { - return Get() == kForward; + return Get() == DoubleSolenoid::Value::kForward; } bool DoubleSolenoidSim::IsReverse() { - return Get() == kReverse; + return Get() == DoubleSolenoid::Value::kReverse; } bool DoubleSolenoidSim::IsOff() { - return Get() == kOff; + return Get() == DoubleSolenoid::Value::kOff; } void DoubleSolenoidSim::SetForward() { - Set(kForward); + Set(DoubleSolenoid::Value::kForward); } void DoubleSolenoidSim::SetReverse() { - Set(kReverse); + Set(DoubleSolenoid::Value::kReverse); } void DoubleSolenoidSim::SetOff() { - Set(kOff); + Set(DoubleSolenoid::Value::kOff); } std::shared_ptr DoubleSolenoidSim::GetModuleSim() const { From e337bfd8a7cd11dcc926fd1be947100ffc334943 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sat, 14 Sep 2024 16:41:38 +0000 Subject: [PATCH 07/15] Formatting fixes --- wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp index cbdaf89e4b1..93c8122b990 100644 --- a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp @@ -3,8 +3,8 @@ // the WPILib BSD license file in the root directory of this project. #include "frc/simulation/DoubleSolenoidSim.h" -#include "frc/DoubleSolenoid.h" +#include "frc/DoubleSolenoid.h" #include "frc/PneumaticsBase.h" using namespace frc; From 5eced813456c0d9b69dd56bf7a8b2d415184f1af Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Sat, 14 Sep 2024 13:08:10 -0400 Subject: [PATCH 08/15] simplifications --- wpilibc/src/main/native/cpp/Solenoid.cpp | 4 ++-- .../src/main/native/cpp/simulation/SolenoidSim.cpp | 12 ++++++------ .../main/native/include/frc/simulation/SolenoidSim.h | 4 ++-- .../main/java/edu/wpi/first/wpilibj/Solenoid.java | 6 +++--- .../wpi/first/wpilibj/simulation/SolenoidSim.java | 4 ++-- 5 files changed, 15 insertions(+), 15 deletions(-) diff --git a/wpilibc/src/main/native/cpp/Solenoid.cpp b/wpilibc/src/main/native/cpp/Solenoid.cpp index 85bf2bfcd56..b396673ea60 100644 --- a/wpilibc/src/main/native/cpp/Solenoid.cpp +++ b/wpilibc/src/main/native/cpp/Solenoid.cpp @@ -55,11 +55,11 @@ bool Solenoid::Get() const { } bool Solenoid::IsOn() const { - return Get() == true; + return Get(); } bool Solenoid::IsOff() const { - return Get() == false; + return !Get(); } void Solenoid::SetOn() { diff --git a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp index b0ff903a4df..681b5f7e20e 100644 --- a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp @@ -22,28 +22,28 @@ SolenoidSim::SolenoidSim(PneumaticsModuleType type, int channel) PneumaticsBase::GetDefaultForType(type), type)}, m_channel{channel} {} -bool SolenoidSim::GetOutput() const { +bool SolenoidSim::Get() const { return m_module->GetSolenoidOutput(m_channel); } -void SolenoidSim::SetOutput(bool output) { +void SolenoidSim::Set(bool output) { m_module->SetSolenoidOutput(m_channel, output); } bool SolenoidSim::IsOn() { - return GetOutput() == true; + return Get(); } bool SolenoidSim::IsOff() { - return GetOutput() == false; + return !Get(); } void SolenoidSim::SetOn() { - SetOutput(true); + Set(true); } void SolenoidSim::SetOff() { - SetOutput(false); + Set(false); } std::unique_ptr SolenoidSim::RegisterOutputCallback( diff --git a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h index dbd8c4f0de5..1715e0cbd17 100644 --- a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h @@ -18,8 +18,8 @@ class SolenoidSim { SolenoidSim(PneumaticsModuleType type, int channel); virtual ~SolenoidSim() = default; - bool GetOutput() const; - void SetOutput(bool output); + bool Get() const; + void Set(bool output); /** * Returns true if the solenoid is on. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index 399e7491be6..500b2061555 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -94,7 +94,7 @@ public boolean get() { * @return true if the solenoid is on. */ public boolean isOn() { - return get() == true; + return get(); } /** @@ -103,7 +103,7 @@ public boolean isOn() { * @return true if the solenoid off. */ public boolean isOff() { - return get() == false; + return !get(); } /** Turns the solenoid on. */ @@ -111,7 +111,7 @@ public void setOn() { set(true); } - /** Turns the solenoid off */ + /** Turns the solenoid off. */ public void setOff() { set(false); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java index 04b382c61d3..8ed2a7b2870 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java @@ -60,7 +60,7 @@ public boolean get() { * @return true if the solenoid is on. */ public boolean isOn() { - return get() == true; + return get(); } /** @@ -69,7 +69,7 @@ public boolean isOn() { * @return true if the solenoid off. */ public boolean isOff() { - return get() == false; + return !get(); } /** Turns the solenoid on. */ From a5440830a3c5a1627251eb1d537e83162d269e2e Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Sat, 14 Sep 2024 13:16:02 -0400 Subject: [PATCH 09/15] avoid unnecessary comparisons in booleans --- wpilibc/src/main/native/cpp/Solenoid.cpp | 6 ++++-- wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java | 6 ++++-- .../java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java | 4 ++-- 3 files changed, 10 insertions(+), 6 deletions(-) diff --git a/wpilibc/src/main/native/cpp/Solenoid.cpp b/wpilibc/src/main/native/cpp/Solenoid.cpp index b396673ea60..36f33d1e5db 100644 --- a/wpilibc/src/main/native/cpp/Solenoid.cpp +++ b/wpilibc/src/main/native/cpp/Solenoid.cpp @@ -55,11 +55,13 @@ bool Solenoid::Get() const { } bool Solenoid::IsOn() const { - return Get(); + int currentAll = m_module->GetSolenoids(); + return (currentAll & m_mask) != 0; } bool Solenoid::IsOff() const { - return !Get(); + int currentAll = m_module->GetSolenoids(); + return (currentAll & m_mask) == 0; } void Solenoid::SetOn() { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index 500b2061555..58b4cdb04cd 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -94,7 +94,8 @@ public boolean get() { * @return true if the solenoid is on. */ public boolean isOn() { - return get(); + int currentAll = m_module.getSolenoids(); + return (currentAll & m_mask) != 0; } /** @@ -103,7 +104,8 @@ public boolean isOn() { * @return true if the solenoid off. */ public boolean isOff() { - return !get(); + int currentAll = m_module.getSolenoids(); + return (currentAll & m_mask) == 0; } /** Turns the solenoid on. */ diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java index 8ed2a7b2870..058eb399aaa 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java @@ -60,7 +60,7 @@ public boolean get() { * @return true if the solenoid is on. */ public boolean isOn() { - return get(); + return m_module.getSolenoidOutput(m_channel); } /** @@ -69,7 +69,7 @@ public boolean isOn() { * @return true if the solenoid off. */ public boolean isOff() { - return !get(); + return !m_module.getSolenoidOutput(m_channel); } /** Turns the solenoid on. */ From ff092a3ffe4bba2dc9d30bcfa3a6bcd42263d65b Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Sat, 14 Sep 2024 13:38:11 -0400 Subject: [PATCH 10/15] formatting fix --- .../main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java index 058eb399aaa..72ea9906118 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java @@ -77,7 +77,7 @@ public void setOn() { set(true); } - /** Turns the solenoid off */ + /** Turns the solenoid off. */ public void setOff() { set(false); } From 6a89eecd3d794e791ac37509d6b7a74bc806611c Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Sat, 21 Sep 2024 14:31:39 -0400 Subject: [PATCH 11/15] formatting fixes --- wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp index 029d0e75381..6a9e54c28b9 100644 --- a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp @@ -4,10 +4,10 @@ #include "frc/simulation/DoubleSolenoidSim.h" -#include "frc/DoubleSolenoid.h" #include #include +#include "frc/DoubleSolenoid.h" #include "frc/PneumaticsBase.h" using namespace frc; From 2fd5eebe930f2fcae171d28e4cf3c150e779bf01 Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Sun, 22 Sep 2024 09:40:59 -0400 Subject: [PATCH 12/15] empty From 3fdbd8fe6941430f2d7eb321214f3c0f06d2e8cc Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Thu, 26 Sep 2024 05:42:18 -0400 Subject: [PATCH 13/15] deprecated old functions --- .../native/cpp/simulation/SolenoidSim.cpp | 8 +++ .../include/frc/simulation/SolenoidSim.h | 23 ++++++ .../edu/wpi/first/wpilibj/DoubleSolenoid.java | 72 ++++++++++--------- .../java/edu/wpi/first/wpilibj/Solenoid.java | 56 +++++++++++---- 4 files changed, 113 insertions(+), 46 deletions(-) diff --git a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp index e9c45fd36ac..238fd1b4b46 100644 --- a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp @@ -29,10 +29,18 @@ bool SolenoidSim::Get() const { return m_module->GetSolenoidOutput(m_channel); } +bool SolenoidSim::GetOutput() const { + return m_module->GetSolenoidOutput(m_channel); +} + void SolenoidSim::Set(bool output) { m_module->SetSolenoidOutput(m_channel, output); } +void SolenoidSim::SetOutput(bool output) { + m_module->SetSolenoidOutput(m_channel, output); +} + bool SolenoidSim::IsOn() { return Get(); } diff --git a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h index d3c8ecef53f..c6e9e3d9ec0 100644 --- a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h @@ -18,9 +18,32 @@ class SolenoidSim { SolenoidSim(PneumaticsModuleType type, int channel); ~SolenoidSim() = default; + /** + * Returns the solenoid output. + * @return the solenoid output. + */ bool Get() const; + + /** + * Returns the solenoid output. + * @return the solenoid output. + */ + [[deprecated("Use Get method instead.")]] + bool GetOutput() const; + + /** + * Sets the solenoid output. + * @param output The new solenoid output. + */ void Set(bool output); + /** + * Sets the solenoid output. + * @param output The new solenoid output. + */ + [[deprecated("Use Set method instead.")]] + void SetOutput(bool output); + /** * Returns true if the solenoid is on. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java index c06ff94cf7e..ea9be1f6e05 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -12,10 +12,13 @@ import edu.wpi.first.util.sendable.SendableRegistry; /** - * DoubleSolenoid class for running 2 channels of high voltage Digital Output on the pneumatics + * DoubleSolenoid class for running 2 channels of high voltage Digital Output on + * the pneumatics * module. * - *

The DoubleSolenoid class is typically used for pneumatics solenoids that have two positions + *

+ * The DoubleSolenoid class is typically used for pneumatics solenoids that have + * two positions * controlled by two separate channels. */ public class DoubleSolenoid implements Sendable, AutoCloseable { @@ -39,7 +42,7 @@ public enum Value { /** * Constructs a double solenoid for a default module of a specific module type. * - * @param moduleType The module type to use. + * @param moduleType The module type to use. * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ @@ -49,14 +52,15 @@ public DoubleSolenoid( } /** - * Constructs a double solenoid for a specified module of a specific module type. + * Constructs a double solenoid for a specified module of a specific module + * type. * - * @param module The module of the solenoid module to use. - * @param moduleType The module type to use. + * @param module The module of the solenoid module to use. + * @param moduleType The module type to use. * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ - @SuppressWarnings({"PMD.UseTryWithResources", "this-escape"}) + @SuppressWarnings({ "PMD.UseTryWithResources", "this-escape" }) public DoubleSolenoid( final int module, final PneumaticsModuleType moduleType, @@ -125,16 +129,30 @@ public synchronized void close() { * @param value The value to set (Off, Forward, Reverse) */ public void set(final Value value) { - int setValue = - switch (value) { - case kOff -> 0; - case kForward -> m_forwardMask; - case kReverse -> m_reverseMask; - }; + int setValue = switch (value) { + case kOff -> 0; + case kForward -> m_forwardMask; + case kReverse -> m_reverseMask; + }; m_module.setSolenoids(m_mask, setValue); } + /** Sets the double solenoid to a forward state. */ + public void setForward() { + set(Value.kForward); + } + + /** Sets the double solenoid to a reverse state. */ + public void setReverse() { + set(Value.kReverse); + } + + /** Sets the double solenoid to a off state. */ + public void setOff() { + set(Value.kOff); + } + /** * Read the current value of the solenoid. * @@ -179,26 +197,14 @@ public boolean isOff() { return get() == Value.kOff; } - /** Sets the double solenoid to a forward state. */ - public void setForward() { - set(Value.kForward); - } - - /** Sets the double solenoid to a reverse state. */ - public void setReverse() { - set(Value.kReverse); - } - - /** Sets the double solenoid to a off state. */ - public void setOff() { - set(Value.kOff); - } - /** * Toggle the value of the solenoid. * - *

If the solenoid is set to forward, it'll be set to reverse. If the solenoid is set to - * reverse, it'll be set to forward. If the solenoid is set to off, nothing happens. + *

+ * If the solenoid is set to forward, it'll be set to reverse. If the solenoid + * is set to + * reverse, it'll be set to forward. If the solenoid is set to off, nothing + * happens. */ public void toggle() { Value value = get(); @@ -229,7 +235,8 @@ public int getRevChannel() { } /** - * Check if the forward solenoid is Disabled. If a solenoid is shorted, it is added to the + * Check if the forward solenoid is Disabled. If a solenoid is shorted, it is + * added to the * DisabledList and disabled until power cycle, or until faults are cleared. * * @return If solenoid is disabled due to short. @@ -239,7 +246,8 @@ public boolean isFwdSolenoidDisabled() { } /** - * Check if the reverse solenoid is Disabled. If a solenoid is shorted, it is added to the + * Check if the reverse solenoid is Disabled. If a solenoid is shorted, it is + * added to the * DisabledList and disabled until power cycle, or until faults are cleared. * * @return If solenoid is disabled due to short. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index 58b4cdb04cd..03b58850750 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -12,9 +12,12 @@ import edu.wpi.first.util.sendable.SendableRegistry; /** - * Solenoid class for running high voltage Digital Output on a pneumatics module. + * Solenoid class for running high voltage Digital Output on a pneumatics + * module. * - *

The Solenoid class is typically used for pneumatic solenoids, but could be used for any device + *

+ * The Solenoid class is typically used for pneumatic solenoids, but could be + * used for any device * within the current spec of the module. */ public class Solenoid implements Sendable, AutoCloseable { @@ -26,7 +29,7 @@ public class Solenoid implements Sendable, AutoCloseable { * Constructs a solenoid for a default module and specified type. * * @param moduleType The module type to use. - * @param channel The channel the solenoid is on. + * @param channel The channel the solenoid is on. */ public Solenoid(final PneumaticsModuleType moduleType, final int channel) { this(PneumaticsBase.getDefaultForType(moduleType), moduleType, channel); @@ -35,9 +38,9 @@ public Solenoid(final PneumaticsModuleType moduleType, final int channel) { /** * Constructs a solenoid for a specified module and type. * - * @param module The module ID to use. + * @param module The module ID to use. * @param moduleType The module type to use. - * @param channel The channel the solenoid is on. + * @param channel The channel the solenoid is on. */ @SuppressWarnings("this-escape") public Solenoid(final int module, final PneumaticsModuleType moduleType, final int channel) { @@ -71,7 +74,8 @@ public void close() { /** * Set the value of a solenoid. * - * @param on True will turn the solenoid output on. False will turn the solenoid output off. + * @param on True will turn the solenoid output on. False will turn the solenoid + * output off. */ public void set(boolean on) { int value = on ? (0xFFFF & m_mask) : 0; @@ -81,13 +85,27 @@ public void set(boolean on) { /** * Read the current value of the solenoid. * - * @return True if the solenoid output is on or false if the solenoid output is off. + * @return True if the solenoid output is on or false if the solenoid output is + * off. */ public boolean get() { int currentAll = m_module.getSolenoids(); return (currentAll & m_mask) != 0; } + /** + * Read the current value of the solenoid. + * + * @return True if the solenoid output is on or false if the solenoid output is + * off. + * @deprecated Use get instead + */ + @Deprecated + public boolean getOutput() { + int currentAll = m_module.getSolenoids(); + return (currentAll & m_mask) != 0; + } + /** * Returns true if the solenoid is on. * @@ -121,7 +139,9 @@ public void setOff() { /** * Toggle the value of the solenoid. * - *

If the solenoid is set to on, it'll be turned off. If the solenoid is set to off, it'll be + *

+ * If the solenoid is set to on, it'll be turned off. If the solenoid is set to + * off, it'll be * turned on. */ public void toggle() { @@ -138,7 +158,8 @@ public int getChannel() { } /** - * Check if solenoid is DisabledListed. If a solenoid is shorted, it is added to the Disabled List + * Check if solenoid is DisabledListed. If a solenoid is shorted, it is added to + * the Disabled List * and disabled until power cycle, or until faults are cleared. * * @return If solenoid is disabled due to short. @@ -148,13 +169,19 @@ public boolean isDisabled() { } /** - * Set the pulse duration in the pneumatics module. This is used in conjunction with the - * startPulse method to allow the pneumatics module to control the timing of a pulse. + * Set the pulse duration in the pneumatics module. This is used in conjunction + * with the + * startPulse method to allow the pneumatics module to control the timing of a + * pulse. * - *

On the PCM, the timing can be controlled in 0.01 second increments, with a maximum of 2.55 + *

+ * On the PCM, the timing can be controlled in 0.01 second increments, with a + * maximum of 2.55 * seconds. * - *

On the PH, the timing can be controlled in 0.001 second increments, with a maximum of 65.534 + *

+ * On the PH, the timing can be controlled in 0.001 second increments, with a + * maximum of 65.534 * seconds. * * @param durationSeconds The duration of the pulse in seconds. @@ -166,7 +193,8 @@ public void setPulseDuration(double durationSeconds) { } /** - * Trigger the pneumatics module to generate a pulse of the duration set in setPulseDuration. + * Trigger the pneumatics module to generate a pulse of the duration set in + * setPulseDuration. * * @see #setPulseDuration(double) */ From 0566b158c0a8dfa2c9dbe1957a15c75c1330ad9a Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 26 Sep 2024 09:50:42 +0000 Subject: [PATCH 14/15] Formatting fixes --- .../edu/wpi/first/wpilibj/DoubleSolenoid.java | 42 +++++++---------- .../java/edu/wpi/first/wpilibj/Solenoid.java | 46 ++++++------------- 2 files changed, 32 insertions(+), 56 deletions(-) diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java index ea9be1f6e05..08a3c903833 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -12,13 +12,10 @@ import edu.wpi.first.util.sendable.SendableRegistry; /** - * DoubleSolenoid class for running 2 channels of high voltage Digital Output on - * the pneumatics + * DoubleSolenoid class for running 2 channels of high voltage Digital Output on the pneumatics * module. * - *

- * The DoubleSolenoid class is typically used for pneumatics solenoids that have - * two positions + *

The DoubleSolenoid class is typically used for pneumatics solenoids that have two positions * controlled by two separate channels. */ public class DoubleSolenoid implements Sendable, AutoCloseable { @@ -42,7 +39,7 @@ public enum Value { /** * Constructs a double solenoid for a default module of a specific module type. * - * @param moduleType The module type to use. + * @param moduleType The module type to use. * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ @@ -52,15 +49,14 @@ public DoubleSolenoid( } /** - * Constructs a double solenoid for a specified module of a specific module - * type. + * Constructs a double solenoid for a specified module of a specific module type. * - * @param module The module of the solenoid module to use. - * @param moduleType The module type to use. + * @param module The module of the solenoid module to use. + * @param moduleType The module type to use. * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ - @SuppressWarnings({ "PMD.UseTryWithResources", "this-escape" }) + @SuppressWarnings({"PMD.UseTryWithResources", "this-escape"}) public DoubleSolenoid( final int module, final PneumaticsModuleType moduleType, @@ -129,11 +125,12 @@ public synchronized void close() { * @param value The value to set (Off, Forward, Reverse) */ public void set(final Value value) { - int setValue = switch (value) { - case kOff -> 0; - case kForward -> m_forwardMask; - case kReverse -> m_reverseMask; - }; + int setValue = + switch (value) { + case kOff -> 0; + case kForward -> m_forwardMask; + case kReverse -> m_reverseMask; + }; m_module.setSolenoids(m_mask, setValue); } @@ -200,11 +197,8 @@ public boolean isOff() { /** * Toggle the value of the solenoid. * - *

- * If the solenoid is set to forward, it'll be set to reverse. If the solenoid - * is set to - * reverse, it'll be set to forward. If the solenoid is set to off, nothing - * happens. + *

If the solenoid is set to forward, it'll be set to reverse. If the solenoid is set to + * reverse, it'll be set to forward. If the solenoid is set to off, nothing happens. */ public void toggle() { Value value = get(); @@ -235,8 +229,7 @@ public int getRevChannel() { } /** - * Check if the forward solenoid is Disabled. If a solenoid is shorted, it is - * added to the + * Check if the forward solenoid is Disabled. If a solenoid is shorted, it is added to the * DisabledList and disabled until power cycle, or until faults are cleared. * * @return If solenoid is disabled due to short. @@ -246,8 +239,7 @@ public boolean isFwdSolenoidDisabled() { } /** - * Check if the reverse solenoid is Disabled. If a solenoid is shorted, it is - * added to the + * Check if the reverse solenoid is Disabled. If a solenoid is shorted, it is added to the * DisabledList and disabled until power cycle, or until faults are cleared. * * @return If solenoid is disabled due to short. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index 03b58850750..c6584665365 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -12,12 +12,9 @@ import edu.wpi.first.util.sendable.SendableRegistry; /** - * Solenoid class for running high voltage Digital Output on a pneumatics - * module. + * Solenoid class for running high voltage Digital Output on a pneumatics module. * - *

- * The Solenoid class is typically used for pneumatic solenoids, but could be - * used for any device + *

The Solenoid class is typically used for pneumatic solenoids, but could be used for any device * within the current spec of the module. */ public class Solenoid implements Sendable, AutoCloseable { @@ -29,7 +26,7 @@ public class Solenoid implements Sendable, AutoCloseable { * Constructs a solenoid for a default module and specified type. * * @param moduleType The module type to use. - * @param channel The channel the solenoid is on. + * @param channel The channel the solenoid is on. */ public Solenoid(final PneumaticsModuleType moduleType, final int channel) { this(PneumaticsBase.getDefaultForType(moduleType), moduleType, channel); @@ -38,9 +35,9 @@ public Solenoid(final PneumaticsModuleType moduleType, final int channel) { /** * Constructs a solenoid for a specified module and type. * - * @param module The module ID to use. + * @param module The module ID to use. * @param moduleType The module type to use. - * @param channel The channel the solenoid is on. + * @param channel The channel the solenoid is on. */ @SuppressWarnings("this-escape") public Solenoid(final int module, final PneumaticsModuleType moduleType, final int channel) { @@ -74,8 +71,7 @@ public void close() { /** * Set the value of a solenoid. * - * @param on True will turn the solenoid output on. False will turn the solenoid - * output off. + * @param on True will turn the solenoid output on. False will turn the solenoid output off. */ public void set(boolean on) { int value = on ? (0xFFFF & m_mask) : 0; @@ -85,8 +81,7 @@ public void set(boolean on) { /** * Read the current value of the solenoid. * - * @return True if the solenoid output is on or false if the solenoid output is - * off. + * @return True if the solenoid output is on or false if the solenoid output is off. */ public boolean get() { int currentAll = m_module.getSolenoids(); @@ -96,8 +91,7 @@ public boolean get() { /** * Read the current value of the solenoid. * - * @return True if the solenoid output is on or false if the solenoid output is - * off. + * @return True if the solenoid output is on or false if the solenoid output is off. * @deprecated Use get instead */ @Deprecated @@ -139,9 +133,7 @@ public void setOff() { /** * Toggle the value of the solenoid. * - *

- * If the solenoid is set to on, it'll be turned off. If the solenoid is set to - * off, it'll be + *

If the solenoid is set to on, it'll be turned off. If the solenoid is set to off, it'll be * turned on. */ public void toggle() { @@ -158,8 +150,7 @@ public int getChannel() { } /** - * Check if solenoid is DisabledListed. If a solenoid is shorted, it is added to - * the Disabled List + * Check if solenoid is DisabledListed. If a solenoid is shorted, it is added to the Disabled List * and disabled until power cycle, or until faults are cleared. * * @return If solenoid is disabled due to short. @@ -169,19 +160,13 @@ public boolean isDisabled() { } /** - * Set the pulse duration in the pneumatics module. This is used in conjunction - * with the - * startPulse method to allow the pneumatics module to control the timing of a - * pulse. + * Set the pulse duration in the pneumatics module. This is used in conjunction with the + * startPulse method to allow the pneumatics module to control the timing of a pulse. * - *

- * On the PCM, the timing can be controlled in 0.01 second increments, with a - * maximum of 2.55 + *

On the PCM, the timing can be controlled in 0.01 second increments, with a maximum of 2.55 * seconds. * - *

- * On the PH, the timing can be controlled in 0.001 second increments, with a - * maximum of 65.534 + *

On the PH, the timing can be controlled in 0.001 second increments, with a maximum of 65.534 * seconds. * * @param durationSeconds The duration of the pulse in seconds. @@ -193,8 +178,7 @@ public void setPulseDuration(double durationSeconds) { } /** - * Trigger the pneumatics module to generate a pulse of the duration set in - * setPulseDuration. + * Trigger the pneumatics module to generate a pulse of the duration set in setPulseDuration. * * @see #setPulseDuration(double) */ From 83a0ab9f0b8d233b837ada6e699c615b4bcc5157 Mon Sep 17 00:00:00 2001 From: Nicholas Armstrong Date: Thu, 10 Oct 2024 07:46:14 -0400 Subject: [PATCH 15/15] deprecation fixes --- .../main/native/cpp/simulation/SolenoidSim.cpp | 16 ++++------------ .../native/include/frc/simulation/SolenoidSim.h | 16 ++-------------- .../java/edu/wpi/first/wpilibj/Solenoid.java | 12 ------------ .../first/wpilibj/simulation/SolenoidSim.java | 12 ++++++++---- 4 files changed, 14 insertions(+), 42 deletions(-) diff --git a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp index 238fd1b4b46..7826bf8671c 100644 --- a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp @@ -25,36 +25,28 @@ SolenoidSim::SolenoidSim(PneumaticsModuleType type, int channel) PneumaticsBase::GetDefaultForType(type), type)}, m_channel{channel} {} -bool SolenoidSim::Get() const { - return m_module->GetSolenoidOutput(m_channel); -} - bool SolenoidSim::GetOutput() const { return m_module->GetSolenoidOutput(m_channel); } -void SolenoidSim::Set(bool output) { - m_module->SetSolenoidOutput(m_channel, output); -} - void SolenoidSim::SetOutput(bool output) { m_module->SetSolenoidOutput(m_channel, output); } bool SolenoidSim::IsOn() { - return Get(); + return m_module->GetSolenoidOutput(m_channel); } bool SolenoidSim::IsOff() { - return !Get(); + return !m_module->GetSolenoidOutput(m_channel); } void SolenoidSim::SetOn() { - Set(true); + m_module->SetSolenoidOutput(m_channel, true); } void SolenoidSim::SetOff() { - Set(false); + m_module->SetSolenoidOutput(m_channel, false); } std::unique_ptr SolenoidSim::RegisterOutputCallback( diff --git a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h index c6e9e3d9ec0..b1eb1df2848 100644 --- a/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h +++ b/wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h @@ -22,26 +22,14 @@ class SolenoidSim { * Returns the solenoid output. * @return the solenoid output. */ - bool Get() const; - - /** - * Returns the solenoid output. - * @return the solenoid output. - */ - [[deprecated("Use Get method instead.")]] + [[deprecated("Use IsOn or IsOff methods instead.")]] bool GetOutput() const; /** * Sets the solenoid output. * @param output The new solenoid output. */ - void Set(bool output); - - /** - * Sets the solenoid output. - * @param output The new solenoid output. - */ - [[deprecated("Use Set method instead.")]] + [[deprecated("Use SetOn or SetOff methods instead.")]] void SetOutput(bool output); /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index c6584665365..58b4cdb04cd 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -88,18 +88,6 @@ public boolean get() { return (currentAll & m_mask) != 0; } - /** - * Read the current value of the solenoid. - * - * @return True if the solenoid output is on or false if the solenoid output is off. - * @deprecated Use get instead - */ - @Deprecated - public boolean getOutput() { - int currentAll = m_module.getSolenoids(); - return (currentAll & m_mask) != 0; - } - /** * Returns true if the solenoid is on. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java index 72ea9906118..9fb8d1ea547 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SolenoidSim.java @@ -49,8 +49,10 @@ public SolenoidSim(PneumaticsModuleType moduleType, int channel) { * Check the solenoid output. * * @return the solenoid output + * @deprecated Use isOn or isOff instead */ - public boolean get() { + @Deprecated + public boolean getOutput() { return m_module.getSolenoidOutput(m_channel); } @@ -74,20 +76,22 @@ public boolean isOff() { /** Turns the solenoid on. */ public void setOn() { - set(true); + m_module.setSolenoidOutput(m_channel, true); } /** Turns the solenoid off. */ public void setOff() { - set(false); + m_module.setSolenoidOutput(m_channel, false); } /** * Change the solenoid output. * * @param output the new solenoid output + * @deprecated Use setOn or setOff instead. */ - public void set(boolean output) { + @Deprecated + public void setOutput(boolean output) { m_module.setSolenoidOutput(m_channel, output); }