Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

[wpilib] Add on/off, forward/reverse/off boolean methods to Solenoid and DoubleSolenoids #7079

Open
wants to merge 34 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 3 commits
Commits
Show all changes
34 commits
Select commit Hold shift + click to select a range
c69ef55
first draft
narmstro2020 Sep 14, 2024
54baa1d
added C++
narmstro2020 Sep 14, 2024
4bb29b2
Formatting fixes
github-actions[bot] Sep 14, 2024
99398fd
changes made as instructed.
narmstro2020 Sep 14, 2024
8be0795
type fix
narmstro2020 Sep 14, 2024
ccc5a81
fixed enums
narmstro2020 Sep 14, 2024
e337bfd
Formatting fixes
github-actions[bot] Sep 14, 2024
5eced81
simplifications
narmstro2020 Sep 14, 2024
f26fa97
Merge branch 'solenoid-booleans' of https://github.com/narmstro2020/a…
narmstro2020 Sep 14, 2024
a544083
avoid unnecessary comparisons in booleans
narmstro2020 Sep 14, 2024
ff092a3
formatting fix
narmstro2020 Sep 14, 2024
404574c
Merge branch 'solenoid-booleans' of https://github.com/narmstro2020/a…
narmstro2020 Sep 21, 2024
6a89eec
formatting fixes
narmstro2020 Sep 21, 2024
2fd5eeb
empty
narmstro2020 Sep 22, 2024
3fdbd8f
deprecated old functions
narmstro2020 Sep 26, 2024
0566b15
Formatting fixes
github-actions[bot] Sep 26, 2024
612365f
Merge branch 'wpilibsuite:main' into solenoid-booleans
narmstro2020 Sep 29, 2024
f89bd2f
Merge branch 'wpilibsuite:main' into solenoid-booleans
narmstro2020 Oct 1, 2024
1f9687d
Merge branch 'wpilibsuite:main' into solenoid-booleans
narmstro2020 Oct 10, 2024
83a0ab9
deprecation fixes
narmstro2020 Oct 10, 2024
5ca9edb
Merge branch 'solenoid-booleans' of https://github.com/narmstro2020/a…
narmstro2020 Oct 10, 2024
c1df8f7
Merge branch 'wpilibsuite:main' into solenoid-booleans
narmstro2020 Oct 11, 2024
1066b24
Merge branch 'wpilibsuite:main' into solenoid-booleans
narmstro2020 Dec 3, 2024
47ec742
remove deprecation message from SolenoidSim.h
narmstro2020 Dec 21, 2024
05190e9
remove deprecation message from SolenoidSim.java
narmstro2020 Dec 21, 2024
7fe25fa
minor fixes
narmstro2020 Dec 21, 2024
8245f7b
formatting fixes
narmstro2020 Dec 21, 2024
d3d0f53
formatting fixes
narmstro2020 Dec 21, 2024
7333b13
Merge branch 'wpilibsuite:main' into solenoid-booleans
narmstro2020 Dec 21, 2024
88e6c11
fixes for tests
narmstro2020 Dec 21, 2024
aeacdf6
added derprecation to Java Solenoid get method
narmstro2020 Dec 24, 2024
a701a76
fix dep warnings in tests.
narmstro2020 Dec 24, 2024
9adadfc
remove deps, added alias comment
narmstro2020 Dec 26, 2024
5867ba3
formatting fixes.
narmstro2020 Dec 26, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
24 changes: 24 additions & 0 deletions wpilibc/src/main/native/cpp/DoubleSolenoid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down
16 changes: 16 additions & 0 deletions wpilibc/src/main/native/cpp/Solenoid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
}
Expand Down
24 changes: 24 additions & 0 deletions wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<PneumaticsBaseSim> DoubleSolenoidSim::GetModuleSim() const {
return m_module;
}
16 changes: 16 additions & 0 deletions wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<CallbackStore> SolenoidSim::RegisterOutputCallback(
NotifyCallback callback, bool initialNotify) {
return m_module->RegisterSolenoidOutputCallback(m_channel, callback,
Expand Down
33 changes: 33 additions & 0 deletions wpilibc/src/main/native/include/frc/DoubleSolenoid.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,39 @@ 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;
narmstro2020 marked this conversation as resolved.
Show resolved Hide resolved

/**
* 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();
narmstro2020 marked this conversation as resolved.
Show resolved Hide resolved

/**
* 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.
*
Expand Down
26 changes: 26 additions & 0 deletions wpilibc/src/main/native/include/frc/Solenoid.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,32 @@ class Solenoid : public wpi::Sendable, public wpi::SendableHelper<Solenoid> {
*/
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.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<PneumaticsBaseSim> GetModuleSim() const;

private:
Expand Down
26 changes: 26 additions & 0 deletions wpilibc/src/main/native/include/frc/simulation/SolenoidSim.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
narmstro2020 marked this conversation as resolved.
Show resolved Hide resolved

/**
* 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.
*
Expand Down
42 changes: 42 additions & 0 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,48 @@ 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.
*
Expand Down
28 changes: 28 additions & 0 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,34 @@ 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.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
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;

Expand Down Expand Up @@ -67,6 +68,48 @@ 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);
}

narmstro2020 marked this conversation as resolved.
Show resolved Hide resolved
/**
* Set the value of the double solenoid output.
*
Expand Down
Loading
Loading