diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Button.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Button.java
index 4d9d1dac1e..60917d049f 100644
--- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Button.java
+++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Button.java
@@ -17,7 +17,10 @@ import java.util.function.BooleanSupplier;
*
This class represents a subclass of Trigger that is specifically aimed at buttons on an
* operator interface as a common use case of the more generalized Trigger objects. This is a simple
* wrapper around Trigger with the method names renamed to fit the Button object use.
+ *
+ * @deprecated Replace with {@link Trigger}.
*/
+@Deprecated
public class Button extends Trigger {
/**
* Default constructor; creates a button that is never pressed.
@@ -31,7 +34,9 @@ public class Button extends Trigger {
* Creates a new button with the given condition determining whether it is pressed.
*
* @param isPressed returns whether or not the trigger should be active
+ * @deprecated Replace with Trigger.
*/
+ @Deprecated
public Button(BooleanSupplier isPressed) {
super(isPressed);
}
@@ -41,7 +46,9 @@ public class Button extends Trigger {
*
* @param command the command to start
* @return this button, so calls can be chained
+ * @deprecated Replace with {@link Trigger#onTrue(Command)}
*/
+ @Deprecated
public Button whenPressed(final Command command) {
whenActive(command);
return this;
@@ -53,7 +60,9 @@ public class Button extends Trigger {
* @param toRun the runnable to run
* @param requirements the required subsystems
* @return this button, so calls can be chained
+ * @deprecated Replace with {@link #onTrue(Command)}, creating the InstantCommand manually
*/
+ @Deprecated
public Button whenPressed(final Runnable toRun, Subsystem... requirements) {
whenActive(toRun, requirements);
return this;
@@ -67,7 +76,10 @@ public class Button extends Trigger {
*
* @param command the command to start
* @return this button, so calls can be chained
+ * @deprecated Use {@link #whileTrue(Command)} with {@link
+ * edu.wpi.first.wpilibj2.command.RepeatCommand RepeatCommand}.
*/
+ @Deprecated
public Button whileHeld(final Command command) {
whileActiveContinuous(command);
return this;
@@ -79,7 +91,9 @@ public class Button extends Trigger {
* @param toRun the runnable to run
* @param requirements the required subsystems
* @return this button, so calls can be chained
+ * @deprecated Use {@link #whileTrue(Command)} and construct a RunCommand manually
*/
+ @Deprecated
public Button whileHeld(final Runnable toRun, Subsystem... requirements) {
whileActiveContinuous(toRun, requirements);
return this;
@@ -91,7 +105,9 @@ public class Button extends Trigger {
*
* @param command the command to start
* @return this button, so calls can be chained
+ * @deprecated Replace with {@link Trigger#whileTrue(Command)}
*/
+ @Deprecated
public Button whenHeld(final Command command) {
whileActiveOnce(command);
return this;
@@ -102,7 +118,9 @@ public class Button extends Trigger {
*
* @param command the command to start
* @return this button, so calls can be chained
+ * @deprecated Replace with {@link Trigger#onFalse(Command)}
*/
+ @Deprecated
public Button whenReleased(final Command command) {
whenInactive(command);
return this;
@@ -114,7 +132,9 @@ public class Button extends Trigger {
* @param toRun the runnable to run
* @param requirements the required subsystems
* @return this button, so calls can be chained
+ * @deprecated Replace with {@link Trigger#onFalse(Command)}, creating the InstantCommand manually
*/
+ @Deprecated
public Button whenReleased(final Runnable toRun, Subsystem... requirements) {
whenInactive(toRun, requirements);
return this;
@@ -126,7 +146,9 @@ public class Button extends Trigger {
*
* @param command the command to start
* @return this button, so calls can be chained
+ * @deprecated Replace with {@link Trigger#toggleOnTrue(Command)}
*/
+ @Deprecated
public Button toggleWhenPressed(final Command command) {
toggleWhenActive(command);
return this;
@@ -137,7 +159,10 @@ public class Button extends Trigger {
*
* @param command the command to start
* @return this button, so calls can be chained
+ * @deprecated Instead, pass {@link #rising()} as an end condition to {@link
+ * Command#until(BooleanSupplier)}.
*/
+ @Deprecated
public Button cancelWhenPressed(final Command command) {
cancelWhenActive(command);
return this;
diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/InternalButton.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/InternalButton.java
index 58cf804c16..65bf55bef8 100644
--- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/InternalButton.java
+++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/InternalButton.java
@@ -12,6 +12,7 @@ import java.util.concurrent.atomic.AtomicBoolean;
*
*
This class is provided by the NewCommands VendorDep
*/
+@SuppressWarnings("deprecation")
public class InternalButton extends Button {
// need to be references, so they can be mutated after being captured in the constructor.
private final AtomicBoolean m_pressed;
diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/JoystickButton.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/JoystickButton.java
index d3bf8412f2..617d4bf835 100644
--- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/JoystickButton.java
+++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/JoystickButton.java
@@ -13,6 +13,7 @@ import edu.wpi.first.wpilibj.GenericHID;
*
*
This class is provided by the NewCommands VendorDep
*/
+@SuppressWarnings("deprecation")
public class JoystickButton extends Button {
/**
* Creates a joystick button for triggering commands.
diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/NetworkButton.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/NetworkButton.java
index dafe471b46..d205da3078 100644
--- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/NetworkButton.java
+++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/NetworkButton.java
@@ -16,6 +16,7 @@ import edu.wpi.first.networktables.NetworkTableInstance;
*
*
This class is provided by the NewCommands VendorDep
*/
+@SuppressWarnings("deprecation")
public class NetworkButton extends Button {
/**
* Creates a NetworkButton that commands can be bound to.
diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/POVButton.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/POVButton.java
index 8b39f47f0d..93463a2f70 100644
--- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/POVButton.java
+++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/POVButton.java
@@ -13,6 +13,7 @@ import edu.wpi.first.wpilibj.GenericHID;
*
*
This class is provided by the NewCommands VendorDep
*/
+@SuppressWarnings("deprecation")
public class POVButton extends Button {
/**
* Creates a POV button for triggering commands.
diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java
index f69fc96c23..b83150d1c5 100644
--- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java
+++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java
@@ -22,7 +22,9 @@ import java.util.function.BooleanSupplier;
*
*
This class is provided by the NewCommands VendorDep
*/
-public class Trigger extends BooleanEvent {
+public class Trigger implements BooleanSupplier {
+ private final BooleanEvent m_event;
+
/**
* Creates a new trigger with the given condition/digital signal.
*
@@ -30,7 +32,7 @@ public class Trigger extends BooleanEvent {
* @param signal the digital signal represented.
*/
public Trigger(EventLoop loop, BooleanSupplier signal) {
- super(loop, signal);
+ m_event = new BooleanEvent(loop, signal);
}
/**
@@ -62,18 +64,103 @@ public class Trigger extends BooleanEvent {
}
/**
- * Returns whether or not the trigger is active.
+ * Starts the given command whenever the signal rises from the low state to the high state.
*
- *
This method will be called repeatedly a command is linked to the Trigger.
- *
- *
Functionally identical to {@link Trigger#getAsBoolean()}.
- *
- * @return whether or not the trigger condition is active.
- * @deprecated use {@link #getAsBoolean()}
+ * @param command the command to start
+ * @return this trigger, so calls can be chained
+ * @see #rising()
*/
- @Deprecated
- public final boolean get() {
- return getAsBoolean();
+ public Trigger onTrue(Command command) {
+ requireNonNullParam(command, "command", "onRising");
+ m_event.rising().ifHigh(command::schedule);
+ return this;
+ }
+
+ /**
+ * Starts the given command whenever the signal falls from the high state to the low state.
+ *
+ * @param command the command to start
+ * @return this trigger, so calls can be chained
+ * @see #falling()
+ */
+ public Trigger onFalse(Command command) {
+ requireNonNullParam(command, "command", "onFalling");
+ m_event.falling().ifHigh(command::schedule);
+ return this;
+ }
+
+ /**
+ * Starts the given command when the signal rises to the high state and cancels it when the signal
+ * falls.
+ *
+ *
Doesn't re-start the command in-between.
+ *
+ * @param command the command to start
+ * @return this trigger, so calls can be chained
+ */
+ public Trigger whileTrue(Command command) {
+ requireNonNullParam(command, "command", "whileHigh");
+ m_event.rising().ifHigh(command::schedule);
+ m_event.falling().ifHigh(command::cancel);
+ return this;
+ }
+
+ /**
+ * Starts the given command when the signal falls to the low state and cancels it when the signal
+ * rises.
+ *
+ *
Does not re-start the command in-between.
+ *
+ * @param command the command to start
+ * @return this trigger, so calls can be chained
+ */
+ public Trigger whileFalse(Command command) {
+ requireNonNullParam(command, "command", "whileLow");
+ m_event.falling().ifHigh(command::schedule);
+ m_event.rising().ifHigh(command::cancel);
+ return this;
+ }
+
+ /**
+ * Toggles a command when the signal rises from the low state to the high state.
+ *
+ * @param command the command to toggle
+ * @return this trigger, so calls can be chained
+ */
+ public Trigger toggleOnTrue(Command command) {
+ requireNonNullParam(command, "command", "toggleOnRising");
+ m_event
+ .rising()
+ .ifHigh(
+ () -> {
+ if (!command.isScheduled()) {
+ command.schedule();
+ } else {
+ command.cancel();
+ }
+ });
+ return this;
+ }
+
+ /**
+ * Toggles a command when the signal rises from the low state to the high state.
+ *
+ * @param command the command to toggle
+ * @return this trigger, so calls can be chained
+ */
+ public Trigger toggleOnFalse(Command command) {
+ requireNonNullParam(command, "command", "toggleOnFalling");
+ m_event
+ .falling()
+ .ifHigh(
+ () -> {
+ if (!command.isScheduled()) {
+ command.schedule();
+ } else {
+ command.cancel();
+ }
+ });
+ return this;
}
/**
@@ -81,11 +168,13 @@ public class Trigger extends BooleanEvent {
*
* @param command the command to start
* @return this trigger, so calls can be chained
+ * @deprecated Use {@link #onTrue(Command)} instead.
*/
+ @Deprecated
public Trigger whenActive(final Command command) {
requireNonNullParam(command, "command", "whenActive");
- this.rising().ifHigh(command::schedule);
+ m_event.rising().ifHigh(command::schedule);
return this;
}
@@ -95,7 +184,9 @@ public class Trigger extends BooleanEvent {
* @param toRun the runnable to run
* @param requirements the required subsystems
* @return this trigger, so calls can be chained
+ * @deprecated Replace with {@link #onTrue(Command)}, creating the InstantCommand manually
*/
+ @Deprecated
public Trigger whenActive(final Runnable toRun, Subsystem... requirements) {
return whenActive(new InstantCommand(toRun, requirements));
}
@@ -108,12 +199,17 @@ public class Trigger extends BooleanEvent {
*
* @param command the command to start
* @return this trigger, so calls can be chained
+ * @deprecated Use {@link #whileTrue(Command)} with {@link
+ * edu.wpi.first.wpilibj2.command.RepeatCommand RepeatCommand}, or bind {@link
+ * Command#schedule() command::schedule} to {@link BooleanEvent#ifHigh(Runnable)} (passing no
+ * requirements).
*/
+ @Deprecated
public Trigger whileActiveContinuous(final Command command) {
requireNonNullParam(command, "command", "whileActiveContinuous");
- this.ifHigh(command::schedule);
- this.falling().ifHigh(command::cancel);
+ m_event.ifHigh(command::schedule);
+ m_event.falling().ifHigh(command::cancel);
return this;
}
@@ -124,7 +220,9 @@ public class Trigger extends BooleanEvent {
* @param toRun the runnable to run
* @param requirements the required subsystems
* @return this trigger, so calls can be chained
+ * @deprecated Use {@link #whileTrue(Command)} and construct a RunCommand manually
*/
+ @Deprecated
public Trigger whileActiveContinuous(final Runnable toRun, Subsystem... requirements) {
return whileActiveContinuous(new InstantCommand(toRun, requirements));
}
@@ -135,12 +233,14 @@ public class Trigger extends BooleanEvent {
*
* @param command the command to start
* @return this trigger, so calls can be chained
+ * @deprecated Use {@link #whileTrue(Command)} instead.
*/
+ @Deprecated
public Trigger whileActiveOnce(final Command command) {
requireNonNullParam(command, "command", "whileActiveOnce");
- this.rising().ifHigh(command::schedule);
- this.falling().ifHigh(command::cancel);
+ m_event.rising().ifHigh(command::schedule);
+ m_event.falling().ifHigh(command::cancel);
return this;
}
@@ -150,11 +250,13 @@ public class Trigger extends BooleanEvent {
*
* @param command the command to start
* @return this trigger, so calls can be chained
+ * @deprecated Use {@link #onFalse(Command)} instead.
*/
+ @Deprecated
public Trigger whenInactive(final Command command) {
requireNonNullParam(command, "command", "whenInactive");
- this.falling().ifHigh(command::schedule);
+ m_event.falling().ifHigh(command::schedule);
return this;
}
@@ -165,7 +267,9 @@ public class Trigger extends BooleanEvent {
* @param toRun the runnable to run
* @param requirements the required subsystems
* @return this trigger, so calls can be chained
+ * @deprecated Construct the InstantCommand manually and replace with {@link #onFalse(Command)}
*/
+ @Deprecated
public Trigger whenInactive(final Runnable toRun, Subsystem... requirements) {
return whenInactive(new InstantCommand(toRun, requirements));
}
@@ -175,11 +279,14 @@ public class Trigger extends BooleanEvent {
*
* @param command the command to toggle
* @return this trigger, so calls can be chained
+ * @deprecated Use {@link #toggleOnTrue(Command)} instead.
*/
+ @Deprecated
public Trigger toggleWhenActive(final Command command) {
requireNonNullParam(command, "command", "toggleWhenActive");
- this.rising()
+ m_event
+ .rising()
.ifHigh(
() -> {
if (command.isScheduled()) {
@@ -197,49 +304,57 @@ public class Trigger extends BooleanEvent {
*
* @param command the command to cancel
* @return this trigger, so calls can be chained
+ * @deprecated Instead, pass {@link #rising()} as an end condition to {@link
+ * Command#until(BooleanSupplier)}.
*/
+ @Deprecated
public Trigger cancelWhenActive(final Command command) {
requireNonNullParam(command, "command", "cancelWhenActive");
- this.rising().ifHigh(command::cancel);
+ m_event.rising().ifHigh(command::cancel);
return this;
}
- /* ----------- Super method type redeclarations ----------------- */
+ /**
+ * Get the wrapped BooleanEvent.
+ *
+ * @return the wrapped BooleanEvent instance.
+ */
+ public BooleanEvent getEvent() {
+ return m_event;
+ }
@Override
+ public boolean getAsBoolean() {
+ return m_event.getAsBoolean();
+ }
+
public Trigger and(BooleanSupplier trigger) {
- return cast(super.and(trigger));
+ return cast(m_event.and(trigger));
}
- @Override
public Trigger or(BooleanSupplier trigger) {
- return cast(super.or(trigger));
+ return cast(m_event.or(trigger));
}
- @Override
public Trigger negate() {
- return cast(super.negate());
+ return cast(m_event.negate());
}
- @Override
public Trigger debounce(double seconds) {
return debounce(seconds, Debouncer.DebounceType.kRising);
}
- @Override
public Trigger debounce(double seconds, Debouncer.DebounceType type) {
- return cast(super.debounce(seconds, type));
+ return cast(m_event.debounce(seconds, type));
}
- @Override
public Trigger rising() {
- return cast(super.rising());
+ return cast(m_event.rising());
}
- @Override
public Trigger falling() {
- return cast(super.falling());
+ return cast(m_event.falling());
}
}
diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp
index 84d9d21331..787fc09cd0 100644
--- a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp
+++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Button.cpp
@@ -9,92 +9,91 @@ using namespace frc2;
Button::Button(std::function isPressed) : Trigger(isPressed) {}
Button Button::WhenPressed(Command* command) {
+ WPI_IGNORE_DEPRECATED
WhenActive(command);
- return *this;
-}
-
-Button Button::WhenPressed(CommandPtr&& command) {
- WhenActive(std::move(command));
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
Button Button::WhenPressed(std::function toRun,
std::initializer_list requirements) {
+ WPI_IGNORE_DEPRECATED
WhenActive(std::move(toRun), requirements);
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
Button Button::WhenPressed(std::function toRun,
std::span requirements) {
+ WPI_IGNORE_DEPRECATED
WhenActive(std::move(toRun), requirements);
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
Button Button::WhileHeld(Command* command) {
+ WPI_IGNORE_DEPRECATED
WhileActiveContinous(command);
- return *this;
-}
-
-Button Button::WhileHeld(CommandPtr&& command) {
- WhileActiveContinous(std::move(command));
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
Button Button::WhileHeld(std::function toRun,
std::initializer_list requirements) {
+ WPI_IGNORE_DEPRECATED
WhileActiveContinous(std::move(toRun), requirements);
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
Button Button::WhileHeld(std::function toRun,
std::span requirements) {
+ WPI_IGNORE_DEPRECATED
WhileActiveContinous(std::move(toRun), requirements);
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
Button Button::WhenHeld(Command* command) {
+ WPI_IGNORE_DEPRECATED
WhileActiveOnce(command);
- return *this;
-}
-
-Button Button::WhenHeld(CommandPtr&& command) {
- WhileActiveOnce(std::move(command));
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
Button Button::WhenReleased(Command* command) {
+ WPI_IGNORE_DEPRECATED
WhenInactive(command);
- return *this;
-}
-
-Button Button::WhenReleased(CommandPtr&& command) {
- WhenInactive(std::move(command));
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
Button Button::WhenReleased(std::function toRun,
std::initializer_list requirements) {
+ WPI_IGNORE_DEPRECATED
WhenInactive(std::move(toRun), requirements);
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
Button Button::WhenReleased(std::function toRun,
std::span requirements) {
+ WPI_IGNORE_DEPRECATED
WhenInactive(std::move(toRun), requirements);
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
Button Button::ToggleWhenPressed(Command* command) {
+ WPI_IGNORE_DEPRECATED
ToggleWhenActive(command);
- return *this;
-}
-
-Button Button::ToggleWhenPressed(CommandPtr&& command) {
- ToggleWhenActive(std::move(command));
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
Button Button::CancelWhenPressed(Command* command) {
+ WPI_IGNORE_DEPRECATED
CancelWhenActive(command);
+ WPI_UNIGNORE_DEPRECATED
return *this;
}
diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/NetworkButton.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/NetworkButton.cpp
index 758044938b..e26cd1477c 100644
--- a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/NetworkButton.cpp
+++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/NetworkButton.cpp
@@ -4,8 +4,11 @@
#include "frc2/command/button/NetworkButton.h"
+#include
+
using namespace frc2;
+WPI_IGNORE_DEPRECATED
NetworkButton::NetworkButton(nt::BooleanTopic topic)
: NetworkButton(topic.Subscribe(false)) {}
@@ -13,6 +16,7 @@ NetworkButton::NetworkButton(nt::BooleanSubscriber sub)
: Button([sub = std::make_shared(std::move(sub))] {
return sub->GetTopic().GetInstance().IsConnected() && sub->Get();
}) {}
+WPI_UNIGNORE_DEPRECATED
NetworkButton::NetworkButton(std::shared_ptr table,
std::string_view field)
diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp
index 022bd49ad6..dc225aca33 100644
--- a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp
+++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp
@@ -13,13 +13,101 @@ using namespace frc2;
Trigger::Trigger(const Trigger& other) = default;
-Trigger Trigger::WhenActive(Command* command) {
- this->Rising().IfHigh([command] { command->Schedule(); });
+Trigger Trigger::OnTrue(Command* command) {
+ m_event.Rising().IfHigh([command] { command->Schedule(); });
return *this;
}
-Trigger Trigger::WhenActive(CommandPtr&& command) {
- this->Rising().IfHigh([command = std::move(command)] { command.Schedule(); });
+Trigger Trigger::OnTrue(CommandPtr&& command) {
+ m_event.Rising().IfHigh(
+ [command = std::move(command)] { command.Schedule(); });
+ return *this;
+}
+
+Trigger Trigger::OnFalse(Command* command) {
+ m_event.Falling().IfHigh([command] { command->Schedule(); });
+ return *this;
+}
+
+Trigger Trigger::OnFalse(CommandPtr&& command) {
+ m_event.Falling().IfHigh(
+ [command = std::move(command)] { command.Schedule(); });
+ return *this;
+}
+
+Trigger Trigger::WhileTrue(Command* command) {
+ m_event.Rising().IfHigh([command] { command->Schedule(); });
+ m_event.Falling().IfHigh([command] { command->Cancel(); });
+ return *this;
+}
+
+Trigger Trigger::WhileTrue(CommandPtr&& command) {
+ auto ptr = std::make_shared(std::move(command));
+ m_event.Rising().IfHigh([ptr] { ptr->Schedule(); });
+ m_event.Falling().IfHigh([ptr] { ptr->Cancel(); });
+ return *this;
+}
+
+Trigger Trigger::WhileFalse(Command* command) {
+ m_event.Falling().IfHigh([command] { command->Schedule(); });
+ m_event.Rising().IfHigh([command] { command->Cancel(); });
+ return *this;
+}
+
+Trigger Trigger::WhileFalse(CommandPtr&& command) {
+ auto ptr = std::make_shared(std::move(command));
+ m_event.Falling().IfHigh([ptr] { ptr->Schedule(); });
+ m_event.Rising().IfHigh([ptr] { ptr->Cancel(); });
+ return *this;
+}
+
+Trigger Trigger::ToggleOnTrue(Command* command) {
+ m_event.Rising().IfHigh([command] {
+ if (command->IsScheduled()) {
+ command->Cancel();
+ } else {
+ command->Schedule();
+ }
+ });
+ return *this;
+}
+
+Trigger Trigger::ToggleOnTrue(CommandPtr&& command) {
+ m_event.Rising().IfHigh([command = std::move(command)] {
+ if (command.IsScheduled()) {
+ command.Cancel();
+ } else {
+ command.Schedule();
+ }
+ });
+ return *this;
+}
+
+Trigger Trigger::ToggleOnFalse(Command* command) {
+ m_event.Falling().IfHigh([command] {
+ if (command->IsScheduled()) {
+ command->Cancel();
+ } else {
+ command->Schedule();
+ }
+ });
+ return *this;
+}
+
+Trigger Trigger::ToggleOnFalse(CommandPtr&& command) {
+ m_event.Falling().IfHigh([command = std::move(command)] {
+ if (command.IsScheduled()) {
+ command.Cancel();
+ } else {
+ command.Schedule();
+ }
+ });
+ return *this;
+}
+
+WPI_IGNORE_DEPRECATED
+Trigger Trigger::WhenActive(Command* command) {
+ m_event.Rising().IfHigh([command] { command->Schedule(); });
return *this;
}
@@ -35,15 +123,8 @@ Trigger Trigger::WhenActive(std::function toRun,
}
Trigger Trigger::WhileActiveContinous(Command* command) {
- this->IfHigh([command] { command->Schedule(); });
- this->Falling().IfHigh([command] { command->Cancel(); });
- return *this;
-}
-
-Trigger Trigger::WhileActiveContinous(CommandPtr&& command) {
- auto ptr = std::make_shared(std::move(command));
- this->IfHigh([ptr] { ptr->Schedule(); });
- this->Falling().IfHigh([ptr] { ptr->Cancel(); });
+ m_event.IfHigh([command] { command->Schedule(); });
+ m_event.Falling().IfHigh([command] { command->Cancel(); });
return *this;
}
@@ -60,26 +141,13 @@ Trigger Trigger::WhileActiveContinous(
}
Trigger Trigger::WhileActiveOnce(Command* command) {
- this->Rising().IfHigh([command] { command->Schedule(); });
- this->Falling().IfHigh([command] { command->Cancel(); });
- return *this;
-}
-
-Trigger Trigger::WhileActiveOnce(CommandPtr&& command) {
- auto ptr = std::make_shared(std::move(command));
- this->Rising().IfHigh([ptr] { ptr->Schedule(); });
- this->Falling().IfHigh([ptr] { ptr->Cancel(); });
+ m_event.Rising().IfHigh([command] { command->Schedule(); });
+ m_event.Falling().IfHigh([command] { command->Cancel(); });
return *this;
}
Trigger Trigger::WhenInactive(Command* command) {
- this->Falling().IfHigh([command] { command->Schedule(); });
- return *this;
-}
-
-Trigger Trigger::WhenInactive(CommandPtr&& command) {
- this->Falling().IfHigh(
- [command = std::move(command)] { command.Schedule(); });
+ m_event.Falling().IfHigh([command] { command->Schedule(); });
return *this;
}
@@ -95,7 +163,7 @@ Trigger Trigger::WhenInactive(std::function toRun,
}
Trigger Trigger::ToggleWhenActive(Command* command) {
- this->Rising().IfHigh([command] {
+ m_event.Rising().IfHigh([command] {
if (command->IsScheduled()) {
command->Cancel();
} else {
@@ -105,18 +173,12 @@ Trigger Trigger::ToggleWhenActive(Command* command) {
return *this;
}
-Trigger Trigger::ToggleWhenActive(CommandPtr&& command) {
- this->Rising().IfHigh([command = std::move(command)] {
- if (command.IsScheduled()) {
- command.Cancel();
- } else {
- command.Schedule();
- }
- });
- return *this;
-}
-
Trigger Trigger::CancelWhenActive(Command* command) {
- this->Rising().IfHigh([command] { command->Cancel(); });
+ m_event.Rising().IfHigh([command] { command->Cancel(); });
return *this;
}
+WPI_UNIGNORE_DEPRECATED
+
+BooleanEvent Trigger::GetEvent() const {
+ return m_event;
+}
diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h b/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h
index 5a1956eb8f..bb19ee9d16 100644
--- a/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h
+++ b/wpilibNewCommands/src/main/native/include/frc2/command/button/Button.h
@@ -9,6 +9,8 @@
#include
#include
+#include
+
#include "Trigger.h"
#include "frc2/command/CommandPtr.h"
@@ -28,13 +30,17 @@ class Button : public Trigger {
* Create a new button that is pressed when the given condition is true.
*
* @param isPressed Whether the button is pressed.
+ * @deprecated Replace with Trigger
*/
+ WPI_DEPRECATED("Replace with Trigger")
explicit Button(std::function isPressed);
/**
* Create a new button that is pressed active (default constructor) - activity
* can be further determined by subclass code.
+ * @deprecated Replace with Trigger
*/
+ WPI_DEPRECATED("Replace with Trigger")
Button() = default;
/**
@@ -44,19 +50,11 @@ class Button : public Trigger {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Replace with Trigger::OnTrue()
*/
+ WPI_DEPRECATED("Replace with Trigger#OnTrue()")
Button WhenPressed(Command* command);
- /**
- * Binds a command to start when the button is pressed. Transfers
- * command ownership to the button scheduler, so the user does not have to
- * worry about lifespan.
- *
- * @param command The command to bind.
- * @return The trigger, for chained calls.
- */
- Button WhenPressed(CommandPtr&& command);
-
/**
* Binds a command to start when the button is pressed. Transfers
* command ownership to the button scheduler, so the user does not have to
@@ -65,9 +63,11 @@ class Button : public Trigger {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Replace with Trigger::OnTrue()
*/
template >>>
+ WPI_DEPRECATED("Replace with Trigger#OnTrue()")
Button WhenPressed(T&& command) {
WhenActive(std::forward(command));
return *this;
@@ -78,7 +78,9 @@ class Button : public Trigger {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Replace with Trigger::OnTrue(cmd::RunOnce())
*/
+ WPI_DEPRECATED("Replace with Trigger#OnTrue(cmd::RunOnce())")
Button WhenPressed(std::function toRun,
std::initializer_list requirements);
@@ -87,7 +89,9 @@ class Button : public Trigger {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Replace with Trigger::OnTrue(cmd::RunOnce())
*/
+ WPI_DEPRECATED("Replace with Trigger#OnTrue(cmd::RunOnce())")
Button WhenPressed(std::function toRun,
std::span requirements = {});
@@ -98,19 +102,11 @@ class Button : public Trigger {
*
* @param command The command to bind.
* @return The button, for chained calls.
+ * @deprecated Replace with Trigger::WhileTrue(command.Repeatedly())
*/
+ WPI_DEPRECATED("Replace with Trigger#WhileTrue(command.Repeatedly())")
Button WhileHeld(Command* command);
- /**
- * Binds a command to be started repeatedly while the button is pressed, and
- * canceled when it is released. Transfers command ownership to the button
- * scheduler, so the user does not have to worry about lifespan.
- *
- * @param command The command to bind.
- * @return The button, for chained calls.
- */
- Button WhileHeld(CommandPtr&& command);
-
/**
* Binds a command to be started repeatedly while the button is pressed, and
* canceled when it is released. Transfers command ownership to the button
@@ -119,9 +115,11 @@ class Button : public Trigger {
*
* @param command The command to bind.
* @return The button, for chained calls.
+ * @deprecated Replace with Trigger::WhileTrue(command.Repeatedly())
*/
template >>>
+ WPI_DEPRECATED("Replace with Trigger#WhileTrue(command.Repeatedly())")
Button WhileHeld(T&& command) {
WhileActiveContinous(std::forward(command));
return *this;
@@ -132,7 +130,9 @@ class Button : public Trigger {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Replace with Trigger::WhileTrue(cmd::Run())
*/
+ WPI_DEPRECATED("Replace with Trigger#WhileTrue(cmd::Run())")
Button WhileHeld(std::function toRun,
std::initializer_list requirements);
@@ -141,7 +141,9 @@ class Button : public Trigger {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Replace with Trigger::WhileTrue(cmd::Run())
*/
+ WPI_DEPRECATED("Replace with Trigger#WhileTrue(cmd::Run())")
Button WhileHeld(std::function toRun,
std::span requirements = {});
@@ -152,19 +154,11 @@ class Button : public Trigger {
*
* @param command The command to bind.
* @return The button, for chained calls.
+ * @deprecated Replace with Trigger::WhileTrue()
*/
+ WPI_DEPRECATED("Replace with Trigger#WhileTrue()")
Button WhenHeld(Command* command);
- /**
- * Binds a command to be started when the button is pressed, and canceled
- * when it is released. Transfers command ownership to the button scheduler,
- * so the user does not have to worry about lifespan.
- *
- * @param command The command to bind.
- * @return The button, for chained calls.
- */
- Button WhenHeld(CommandPtr&& command);
-
/**
* Binds a command to be started when the button is pressed, and canceled
* when it is released. Transfers command ownership to the button scheduler,
@@ -173,9 +167,11 @@ class Button : public Trigger {
*
* @param command The command to bind.
* @return The button, for chained calls.
+ * @deprecated Replace with Trigger::WhileTrue()
*/
template >>>
+ WPI_DEPRECATED("Replace with Trigger#WhileTrue()")
Button WhenHeld(T&& command) {
WhileActiveOnce(std::forward(command));
return *this;
@@ -188,19 +184,11 @@ class Button : public Trigger {
*
* @param command The command to bind.
* @return The button, for chained calls.
+ * @deprecated Replace with Trigger::OnFalse()
*/
+ WPI_DEPRECATED("Replace with Trigger#OnFalse()")
Button WhenReleased(Command* command);
- /**
- * Binds a command to start when the button is pressed. Transfers
- * command ownership to the button scheduler, so the user does not have to
- * worry about lifespan.
- *
- * @param command The command to bind.
- * @return The button, for chained calls.
- */
- Button WhenReleased(CommandPtr&& command);
-
/**
* Binds a command to start when the button is pressed. Transfers
* command ownership to the button scheduler, so the user does not have to
@@ -209,9 +197,11 @@ class Button : public Trigger {
*
* @param command The command to bind.
* @return The button, for chained calls.
+ * @deprecated Replace with Trigger::OnFalse()
*/
template >>>
+ WPI_DEPRECATED("Replace with Trigger#OnFalse()")
Button WhenReleased(T&& command) {
WhenInactive(std::forward(command));
return *this;
@@ -222,7 +212,9 @@ class Button : public Trigger {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Replace with Trigger::OnFalse(cmd::RunOnce())
*/
+ WPI_DEPRECATED("Replace with Trigger#OnFalse(cmd::RunOnce())")
Button WhenReleased(std::function toRun,
std::initializer_list requirements);
@@ -231,7 +223,9 @@ class Button : public Trigger {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Replace with Trigger::OnFalse(cmd::RunOnce())
*/
+ WPI_DEPRECATED("Replace with Trigger#OnFalse(cmd::RunOnce())")
Button WhenReleased(std::function toRun,
std::span requirements = {});
@@ -242,19 +236,11 @@ class Button : public Trigger {
*
* @param command The command to bind.
* @return The button, for chained calls.
+ * @deprecated Replace with Trigger::ToggleOnTrue()
*/
+ WPI_DEPRECATED("Replace with Trigger#ToggleOnTrue()")
Button ToggleWhenPressed(Command* command);
- /**
- * Binds a command to start when the button is pressed, and be canceled when
- * it is pessed again. Transfers command ownership to the button scheduler,
- * so the user does not have to worry about lifespan.
- *
- * @param command The command to bind.
- * @return The button, for chained calls.
- */
- Button ToggleWhenPressed(CommandPtr&& command);
-
/**
* Binds a command to start when the button is pressed, and be canceled when
* it is pessed again. Transfers command ownership to the button scheduler,
@@ -263,9 +249,11 @@ class Button : public Trigger {
*
* @param command The command to bind.
* @return The button, for chained calls.
+ * @deprecated Replace with Trigger::ToggleOnTrue()
*/
template >>>
+ WPI_DEPRECATED("Replace with Trigger#ToggleOnTrue()")
Button ToggleWhenPressed(T&& command) {
ToggleWhenActive(std::forward(command));
return *this;
@@ -278,7 +266,10 @@ class Button : public Trigger {
*
* @param command The command to bind.
* @return The button, for chained calls.
+ * @deprecated Use Rising() as a command end condition with Until() instead.
*/
+ WPI_DEPRECATED(
+ "Use Rising() as a command end condition with Until() instead.")
Button CancelWhenPressed(Command* command);
};
} // namespace frc2
diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/button/JoystickButton.h b/wpilibNewCommands/src/main/native/include/frc2/command/button/JoystickButton.h
index 7d74358be8..b72fb863b1 100644
--- a/wpilibNewCommands/src/main/native/include/frc2/command/button/JoystickButton.h
+++ b/wpilibNewCommands/src/main/native/include/frc2/command/button/JoystickButton.h
@@ -4,6 +4,7 @@
#pragma once
#include
+#include
#include "Button.h"
@@ -24,9 +25,11 @@ class JoystickButton : public Button {
* @param joystick The joystick on which the button is located.
* @param buttonNumber The number of the button on the joystic.
*/
+ WPI_IGNORE_DEPRECATED
explicit JoystickButton(frc::GenericHID* joystick, int buttonNumber)
: Button([joystick, buttonNumber] {
return joystick->GetRawButton(buttonNumber);
}) {}
+ WPI_UNIGNORE_DEPRECATED
};
} // namespace frc2
diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/button/POVButton.h b/wpilibNewCommands/src/main/native/include/frc2/command/button/POVButton.h
index c0f0e6b782..7ee1590794 100644
--- a/wpilibNewCommands/src/main/native/include/frc2/command/button/POVButton.h
+++ b/wpilibNewCommands/src/main/native/include/frc2/command/button/POVButton.h
@@ -4,6 +4,7 @@
#pragma once
#include
+#include
#include "Button.h"
@@ -25,9 +26,11 @@ class POVButton : public Button {
* @param angle The angle of the POV corresponding to a button press.
* @param povNumber The number of the POV on the joystick.
*/
+ WPI_IGNORE_DEPRECATED
POVButton(frc::GenericHID* joystick, int angle, int povNumber = 0)
: Button([joystick, angle, povNumber] {
return joystick->GetPOV(povNumber) == angle;
}) {}
+ WPI_UNIGNORE_DEPRECATED
};
} // namespace frc2
diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h b/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h
index 7736461399..30ee4b336c 100644
--- a/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h
+++ b/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h
@@ -14,6 +14,7 @@
#include
#include
#include
+#include
#include "frc2/command/Command.h"
#include "frc2/command/CommandScheduler.h"
@@ -21,14 +22,14 @@
namespace frc2 {
class Command;
/**
- * This class is a command-based wrapper around {@link BooleanEvent}, providing
- * an easy way to link commands to inputs.
+ * This class is a command-based wrapper around {@link frc::BooleanEvent},
+ * providing an easy way to link commands to inputs.
*
* This class is provided by the NewCommands VendorDep
*
* @see Button
*/
-class Trigger : public frc::BooleanEvent {
+class Trigger {
public:
/**
* Creates a new trigger with the given condition determining whether it is
@@ -39,8 +40,8 @@ class Trigger : public frc::BooleanEvent {
* @param isActive returns whether or not the trigger should be active
*/
explicit Trigger(std::function isActive)
- : BooleanEvent{CommandScheduler::GetInstance().GetDefaultButtonLoop(),
- std::move(isActive)} {}
+ : m_event{CommandScheduler::GetInstance().GetDefaultButtonLoop(),
+ std::move(isActive)} {}
/**
* Create a new trigger that is active when the given condition is true.
@@ -49,7 +50,7 @@ class Trigger : public frc::BooleanEvent {
* @param isActive Whether the trigger is active.
*/
Trigger(frc::EventLoop* loop, std::function isActive)
- : BooleanEvent{loop, std::move(isActive)} {}
+ : m_event{loop, std::move(isActive)} {}
/**
* Create a new trigger that is never active (default constructor) - activity
@@ -59,6 +60,143 @@ class Trigger : public frc::BooleanEvent {
Trigger(const Trigger& other);
+ /**
+ * Starts the given command whenever the signal rises from `false` to `true`.
+ *
+ * Takes a raw pointer, and so is non-owning; users are responsible for the
+ * lifespan of the command.
+ *
+ * @param command the command to start
+ * @return this trigger, so calls can be chained
+ * @see #Rising()
+ */
+ Trigger OnTrue(Command* command);
+
+ /**
+ * Starts the given command whenever the signal rises from `false` to `true`.
+ * Moves command ownership to the button scheduler.
+ *
+ * @param command The command to bind.
+ * @return The trigger, for chained calls.
+ */
+ Trigger OnTrue(CommandPtr&& command);
+
+ /**
+ * Starts the given command whenever the signal falls from `true` to `false`.
+ *
+ *
Takes a raw pointer, and so is non-owning; users are responsible for the
+ * lifespan of the command.
+ *
+ * @param command the command to start
+ * @return this trigger, so calls can be chained
+ * @see #Falling()
+ */
+ Trigger OnFalse(Command* command);
+
+ /**
+ * Starts the given command whenever the signal falls from `true` to `false`.
+ *
+ * @param command The command to bind.
+ * @return The trigger, for chained calls.
+ */
+ Trigger OnFalse(CommandPtr&& command);
+
+ /**
+ * Starts the given command when the signal rises to `true` and cancels it
+ * when the signal falls to `false`.
+ *
+ *
Doesn't re-start the command in-between.
+ *
+ *
Takes a raw pointer, and so is non-owning; users are responsible for the
+ * lifespan of the command.
+ *
+ * @param command the command to start
+ * @return this trigger, so calls can be chained
+ */
+ Trigger WhileTrue(Command* command);
+
+ /**
+ * Starts the given command when the signal rises to `true` and cancels it
+ * when the signal falls to `false`. Moves command ownership to the button
+ * scheduler.
+ *
+ * @param command The command to bind.
+ * @return The trigger, for chained calls.
+ */
+ Trigger WhileTrue(CommandPtr&& command);
+
+ /**
+ * Starts the given command when the signal falls to `false` and cancels
+ * it when the signal rises.
+ *
+ *
Doesn't re-start the command in-between.
+ *
+ *
Takes a raw pointer, and so is non-owning; users are responsible for the
+ * lifespan of the command.
+ *
+ * @param command the command to start
+ * @return this trigger, so calls can be chained
+ */
+ Trigger WhileFalse(Command* command);
+
+ /**
+ * Starts the given command when the signal falls to `false` and cancels
+ * it when the signal rises. Moves command ownership to the button
+ * scheduler.
+ *
+ * @param command The command to bind.
+ * @return The trigger, for chained calls.
+ */
+ Trigger WhileFalse(CommandPtr&& command);
+
+ /**
+ * Toggles a command when the signal rises from `false` to the high
+ * state.
+ *
+ *
Takes a raw pointer, and so is non-owning; users are responsible for the
+ * lifespan of the command.
+ *
+ * @param command the command to toggle
+ * @return this trigger, so calls can be chained
+ */
+ Trigger ToggleOnTrue(Command* command);
+
+ /**
+ * Toggles a command when the signal rises from `false` to the high
+ * state.
+ *
+ *
Takes a raw pointer, and so is non-owning; users are responsible for the
+ * lifespan of the command.
+ *
+ * @param command the command to toggle
+ * @return this trigger, so calls can be chained
+ */
+ Trigger ToggleOnTrue(CommandPtr&& command);
+
+ /**
+ * Toggles a command when the signal falls from `true` to the low
+ * state.
+ *
+ *
Takes a raw pointer, and so is non-owning; users are responsible for the
+ * lifespan of the command.
+ *
+ * @param command the command to toggle
+ * @return this trigger, so calls can be chained
+ */
+ Trigger ToggleOnFalse(Command* command);
+
+ /**
+ * Toggles a command when the signal falls from `true` to the low
+ * state.
+ *
+ *
Takes a raw pointer, and so is non-owning; users are responsible for the
+ * lifespan of the command.
+ *
+ * @param command the command to toggle
+ * @return this trigger, so calls can be chained
+ */
+ Trigger ToggleOnFalse(CommandPtr&& command);
+
/**
* Binds a command to start when the trigger becomes active. Takes a
* raw pointer, and so is non-owning; users are responsible for the lifespan
@@ -66,18 +204,11 @@ class Trigger : public frc::BooleanEvent {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Use OnTrue(Command) instead
*/
+ WPI_DEPRECATED("Use OnTrue(Command) instead")
Trigger WhenActive(Command* command);
- /**
- * Binds a command to start when the trigger becomes active. Moves
- * command ownership to the button scheduler.
- *
- * @param command The command to bind.
- * @return The trigger, for chained calls.
- */
- Trigger WhenActive(CommandPtr&& command);
-
/**
* Binds a command to start when the trigger becomes active. Transfers
* command ownership to the button scheduler, so the user does not have to
@@ -86,11 +217,13 @@ class Trigger : public frc::BooleanEvent {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Use OnTrue(Command) instead
*/
template >>>
+ WPI_DEPRECATED("Use OnTrue(Command) instead")
Trigger WhenActive(T&& command) {
- this->Rising().IfHigh(
+ m_event.Rising().IfHigh(
[command = std::make_unique>(
std::forward(command))] { command->Schedule(); });
@@ -102,7 +235,11 @@ class Trigger : public frc::BooleanEvent {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Use OnTrue(Command) instead and construct the InstantCommand
+ * manually
*/
+ WPI_DEPRECATED(
+ "Use OnTrue(Command) instead and construct the InstantCommand manually")
Trigger WhenActive(std::function toRun,
std::initializer_list requirements);
@@ -111,7 +248,11 @@ class Trigger : public frc::BooleanEvent {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Use OnTrue(Command) instead and construct the InstantCommand
+ * manually
*/
+ WPI_DEPRECATED(
+ "Use OnTrue(Command) instead and construct the InstantCommand manually")
Trigger WhenActive(std::function toRun,
std::span requirements = {});
@@ -122,19 +263,14 @@ class Trigger : public frc::BooleanEvent {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Use WhileTrue(Command) with RepeatCommand, or bind
+ command::Schedule with IfHigh(std::function).
*/
+ WPI_DEPRECATED(
+ "Use WhileTrue(Command) with RepeatCommand, or bind command::Schedule "
+ "with IfHigh(std::function).")
Trigger WhileActiveContinous(Command* command);
- /**
- * Binds a command to be started repeatedly while the trigger is active, and
- * canceled when it becomes inactive. Moves command ownership to the button
- * scheduler.
- *
- * @param command The command to bind.
- * @return The trigger, for chained calls.
- */
- Trigger WhileActiveContinous(CommandPtr&& command);
-
/**
* Binds a command to be started repeatedly while the trigger is active, and
* canceled when it becomes inactive. Transfers command ownership to the
@@ -143,14 +279,19 @@ class Trigger : public frc::BooleanEvent {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Use WhileTrue(Command) with RepeatCommand, or bind
+ command::Schedule with IfHigh(std::function).
*/
template >>>
+ WPI_DEPRECATED(
+ "Use WhileTrue(Command) with RepeatCommand, or bind command::Schedule "
+ "with IfHigh(std::function).")
Trigger WhileActiveContinous(T&& command) {
std::shared_ptr ptr =
std::make_shared>(std::forward(command));
- this->IfHigh([ptr] { ptr->Schedule(); });
- this->Falling().IfHigh([ptr] { ptr->Cancel(); });
+ m_event.IfHigh([ptr] { ptr->Schedule(); });
+ m_event.Falling().IfHigh([ptr] { ptr->Cancel(); });
return *this;
}
@@ -160,7 +301,9 @@ class Trigger : public frc::BooleanEvent {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Use WhileTrue(Command) and construct a RunCommand manually
*/
+ WPI_DEPRECATED("Use WhileTrue(Command) and construct a RunCommand manually")
Trigger WhileActiveContinous(std::function toRun,
std::initializer_list requirements);
@@ -169,7 +312,9 @@ class Trigger : public frc::BooleanEvent {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Use WhileTrue(Command) and construct a RunCommand manually
*/
+ WPI_DEPRECATED("Use WhileTrue(Command) and construct a RunCommand manually")
Trigger WhileActiveContinous(std::function toRun,
std::span requirements = {});
@@ -180,19 +325,11 @@ class Trigger : public frc::BooleanEvent {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Use WhileTrue(Command) instead.
*/
+ WPI_DEPRECATED("Use WhileTrue(Command) instead.")
Trigger WhileActiveOnce(Command* command);
- /**
- * Binds a command to be started when the trigger becomes active, and
- * canceled when it becomes inactive. Moves command ownership to the button
- * scheduler.
- *
- * @param command The command to bind.
- * @return The trigger, for chained calls.
- */
- Trigger WhileActiveOnce(CommandPtr&& command);
-
/**
* Binds a command to be started when the trigger becomes active, and
* canceled when it becomes inactive. Transfers command ownership to the
@@ -201,15 +338,17 @@ class Trigger : public frc::BooleanEvent {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Use WhileTrue(Command) instead.
*/
template >>>
+ WPI_DEPRECATED("Use WhileTrue(Command) instead.")
Trigger WhileActiveOnce(T&& command) {
std::shared_ptr ptr =
std::make_shared>(std::forward(command));
- this->Rising().IfHigh([ptr] { ptr->Schedule(); });
- this->Falling().IfHigh([ptr] { ptr->Cancel(); });
+ m_event.Rising().IfHigh([ptr] { ptr->Schedule(); });
+ m_event.Falling().IfHigh([ptr] { ptr->Cancel(); });
return *this;
}
@@ -221,18 +360,11 @@ class Trigger : public frc::BooleanEvent {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Use OnFalse(Command) instead.
*/
+ WPI_DEPRECATED("Use OnFalse(Command) instead.")
Trigger WhenInactive(Command* command);
- /**
- * Binds a command to start when the trigger becomes inactive. Moves
- * command ownership to the button scheduler.
- *
- * @param command The command to bind.
- * @return The trigger, for chained calls.
- */
- Trigger WhenInactive(CommandPtr&& command);
-
/**
* Binds a command to start when the trigger becomes inactive. Transfers
* command ownership to the button scheduler, so the user does not have to
@@ -241,11 +373,13 @@ class Trigger : public frc::BooleanEvent {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Use OnFalse(Command) instead.
*/
template >>>
+ WPI_DEPRECATED("Use OnFalse(Command) instead.")
Trigger WhenInactive(T&& command) {
- this->Falling().IfHigh(
+ m_event.Falling().IfHigh(
[command = std::make_unique>(
std::forward(command))] { command->Schedule(); });
@@ -257,7 +391,11 @@ class Trigger : public frc::BooleanEvent {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Use OnFalse(Command) instead and construct the InstantCommand
+ * manually
*/
+ WPI_DEPRECATED(
+ "Use OnFalse(Command) instead and construct the InstantCommand manually")
Trigger WhenInactive(std::function toRun,
std::initializer_list requirements);
@@ -266,7 +404,11 @@ class Trigger : public frc::BooleanEvent {
*
* @param toRun the runnable to execute.
* @param requirements the required subsystems.
+ * @deprecated Use OnFalse(Command) instead and construct the InstantCommand
+ * manually
*/
+ WPI_DEPRECATED(
+ "Use OnFalse(Command) instead and construct the InstantCommand manually")
Trigger WhenInactive(std::function toRun,
std::span requirements = {});
@@ -277,19 +419,11 @@ class Trigger : public frc::BooleanEvent {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Use ToggleOnTrue(Command) instead.
*/
+ WPI_DEPRECATED("Use ToggleOnTrue(Command) instead.")
Trigger ToggleWhenActive(Command* command);
- /**
- * Binds a command to start when the trigger becomes active, and be canceled
- * when it again becomes active. Moves command ownership to the button
- * scheduler.
- *
- * @param command The command to bind.
- * @return The trigger, for chained calls.
- */
- Trigger ToggleWhenActive(CommandPtr&& command);
-
/**
* Binds a command to start when the trigger becomes active, and be canceled
* when it again becomes active. Transfers command ownership to the button
@@ -298,11 +432,13 @@ class Trigger : public frc::BooleanEvent {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Use ToggleOnTrue(Command) instead.
*/
template >>>
+ WPI_DEPRECATED("Use ToggleOnTrue(Command) instead.")
Trigger ToggleWhenActive(T&& command) {
- this->Rising().IfHigh(
+ m_event.Rising().IfHigh(
[command = std::make_unique>(
std::forward(command))] {
if (!command->IsScheduled()) {
@@ -322,7 +458,10 @@ class Trigger : public frc::BooleanEvent {
*
* @param command The command to bind.
* @return The trigger, for chained calls.
+ * @deprecated Use Rising() as a command end condition with Until() instead.
*/
+ WPI_DEPRECATED(
+ "Use Rising() as a command end condition with Until() instead.")
Trigger CancelWhenActive(Command* command);
/**
@@ -330,14 +469,14 @@ class Trigger : public frc::BooleanEvent {
*
* @return a new event representing when this one newly changes to true.
*/
- Trigger Rising() { return BooleanEvent::Rising().CastTo(); }
+ Trigger Rising() { return m_event.Rising().CastTo(); }
/**
* Get a new event that triggers only when this one newly changes to false.
*
* @return a new event representing when this one newly changes to false.
*/
- Trigger Falling() { return BooleanEvent::Falling().CastTo(); }
+ Trigger Falling() { return m_event.Falling().CastTo(); }
/**
* Composes two triggers with logical AND.
@@ -345,7 +484,7 @@ class Trigger : public frc::BooleanEvent {
* @return A trigger which is active when both component triggers are active.
*/
Trigger operator&&(std::function rhs) {
- return BooleanEvent::operator&&(rhs).CastTo();
+ return m_event.operator&&(rhs).CastTo();
}
/**
@@ -354,7 +493,7 @@ class Trigger : public frc::BooleanEvent {
* @return A trigger which is active when either component trigger is active.
*/
Trigger operator||(std::function rhs) {
- return BooleanEvent::operator||(rhs).CastTo();
+ return m_event.operator||(rhs).CastTo();
}
/**
@@ -363,7 +502,7 @@ class Trigger : public frc::BooleanEvent {
* @return A trigger which is active when the component trigger is inactive,
* and vice-versa.
*/
- Trigger operator!() { return BooleanEvent::operator!().CastTo(); }
+ Trigger operator!() { return m_event.operator!().CastTo(); }
/**
* Creates a new debounced trigger from this trigger - it will become active
@@ -376,7 +515,15 @@ class Trigger : public frc::BooleanEvent {
Trigger Debounce(units::second_t debounceTime,
frc::Debouncer::DebounceType type =
frc::Debouncer::DebounceType::kRising) {
- return BooleanEvent::Debounce(debounceTime, type).CastTo();
+ return m_event.Debounce(debounceTime, type).CastTo();
}
+
+ /**
+ * Get the wrapped BooleanEvent instance.
+ */
+ frc::BooleanEvent GetEvent() const;
+
+ private:
+ frc::BooleanEvent m_event;
};
} // namespace frc2
diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/ButtonTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/ButtonTest.java
deleted file mode 100644
index b4a1859a7e..0000000000
--- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/ButtonTest.java
+++ /dev/null
@@ -1,220 +0,0 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
-package edu.wpi.first.wpilibj2.command.button;
-
-import static org.junit.jupiter.api.Assertions.assertEquals;
-import static org.junit.jupiter.api.Assertions.assertFalse;
-import static org.junit.jupiter.api.Assertions.assertTrue;
-import static org.mockito.Mockito.never;
-import static org.mockito.Mockito.times;
-import static org.mockito.Mockito.verify;
-import static org.mockito.Mockito.when;
-
-import edu.wpi.first.wpilibj.simulation.SimHooks;
-import edu.wpi.first.wpilibj2.command.Command;
-import edu.wpi.first.wpilibj2.command.CommandScheduler;
-import edu.wpi.first.wpilibj2.command.CommandTestBase;
-import java.util.concurrent.atomic.AtomicInteger;
-import java.util.function.BooleanSupplier;
-import org.junit.jupiter.api.Test;
-
-class ButtonTest extends CommandTestBase {
- @Test
- void whenPressedTest() {
- CommandScheduler scheduler = CommandScheduler.getInstance();
- MockCommandHolder command1Holder = new MockCommandHolder(true);
- Command command1 = command1Holder.getMock();
-
- InternalButton button = new InternalButton();
- button.setPressed(false);
- button.whenPressed(command1);
- scheduler.run();
- verify(command1, never()).schedule();
- button.setPressed(true);
- scheduler.run();
- scheduler.run();
- verify(command1).schedule();
- }
-
- @Test
- void whenReleasedTest() {
- CommandScheduler scheduler = CommandScheduler.getInstance();
- MockCommandHolder command1Holder = new MockCommandHolder(true);
- Command command1 = command1Holder.getMock();
-
- InternalButton button = new InternalButton();
- button.setPressed(true);
- button.whenReleased(command1);
- scheduler.run();
- verify(command1, never()).schedule();
- button.setPressed(false);
- scheduler.run();
- scheduler.run();
- verify(command1).schedule();
- }
-
- @Test
- void whileHeldTest() {
- CommandScheduler scheduler = CommandScheduler.getInstance();
- MockCommandHolder command1Holder = new MockCommandHolder(true);
- Command command1 = command1Holder.getMock();
-
- InternalButton button = new InternalButton();
- button.setPressed(false);
- button.whileHeld(command1);
- scheduler.run();
- verify(command1, never()).schedule();
- button.setPressed(true);
- scheduler.run();
- scheduler.run();
- verify(command1, times(2)).schedule();
- button.setPressed(false);
- scheduler.run();
- verify(command1).cancel();
- }
-
- @Test
- void whenHeldTest() {
- CommandScheduler scheduler = CommandScheduler.getInstance();
- MockCommandHolder command1Holder = new MockCommandHolder(true);
- Command command1 = command1Holder.getMock();
-
- InternalButton button = new InternalButton();
- button.setPressed(false);
- button.whenHeld(command1);
- scheduler.run();
- verify(command1, never()).schedule();
- button.setPressed(true);
- scheduler.run();
- scheduler.run();
- verify(command1).schedule();
- button.setPressed(false);
- scheduler.run();
- verify(command1).cancel();
- }
-
- @Test
- void toggleWhenPressedTest() {
- CommandScheduler scheduler = CommandScheduler.getInstance();
- MockCommandHolder command1Holder = new MockCommandHolder(true);
- Command command1 = command1Holder.getMock();
-
- InternalButton button = new InternalButton();
- button.setPressed(false);
- button.toggleWhenPressed(command1);
- scheduler.run();
- verify(command1, never()).schedule();
- button.setPressed(true);
- scheduler.run();
- when(command1.isScheduled()).thenReturn(true);
- scheduler.run();
- verify(command1).schedule();
- button.setPressed(false);
- scheduler.run();
- verify(command1, never()).cancel();
- button.setPressed(true);
- scheduler.run();
- verify(command1).cancel();
- }
-
- @Test
- void cancelWhenPressedTest() {
- CommandScheduler scheduler = CommandScheduler.getInstance();
- MockCommandHolder command1Holder = new MockCommandHolder(true);
- Command command1 = command1Holder.getMock();
-
- InternalButton button = new InternalButton();
- button.setPressed(false);
- button.cancelWhenPressed(command1);
- scheduler.run();
- verify(command1, never()).cancel();
- button.setPressed(true);
- scheduler.run();
- scheduler.run();
- verify(command1).cancel();
- }
-
- @Test
- void runnableBindingTest() {
- InternalButton buttonWhenPressed = new InternalButton();
- InternalButton buttonWhileHeld = new InternalButton();
- InternalButton buttonWhenReleased = new InternalButton();
-
- buttonWhenPressed.setPressed(false);
- buttonWhileHeld.setPressed(true);
- buttonWhenReleased.setPressed(true);
-
- AtomicInteger counter = new AtomicInteger(0);
-
- buttonWhenPressed.whenPressed(counter::incrementAndGet);
- buttonWhileHeld.whileHeld(counter::incrementAndGet);
- buttonWhenReleased.whenReleased(counter::incrementAndGet);
-
- CommandScheduler scheduler = CommandScheduler.getInstance();
-
- scheduler.run();
- buttonWhenPressed.setPressed(true);
- buttonWhenReleased.setPressed(false);
- scheduler.run();
-
- assertEquals(counter.get(), 4);
- }
-
- @Test
- void buttonCompositionTest() {
- InternalButton button1 = new InternalButton();
- InternalButton button2 = new InternalButton();
-
- button1.setPressed(true);
- button2.setPressed(false);
-
- assertFalse(button1.and(button2).getAsBoolean());
- assertTrue(button1.or(button2).getAsBoolean());
- assertFalse(button1.negate().getAsBoolean());
- assertTrue(button1.and(button2.negate()).getAsBoolean());
- }
-
- @Test
- void buttonCompositionSupplierTest() {
- InternalButton button1 = new InternalButton();
- BooleanSupplier booleanSupplier = () -> false;
-
- button1.setPressed(true);
-
- assertFalse(button1.and(booleanSupplier).getAsBoolean());
- assertTrue(button1.or(booleanSupplier).getAsBoolean());
- }
-
- @Test
- void debounceTest() {
- CommandScheduler scheduler = CommandScheduler.getInstance();
- MockCommandHolder commandHolder = new MockCommandHolder(true);
- Command command = commandHolder.getMock();
-
- InternalButton button = new InternalButton();
- Trigger debounced = button.debounce(0.1);
-
- debounced.whenActive(command);
-
- button.setPressed(true);
- scheduler.run();
- verify(command, never()).schedule();
-
- SimHooks.stepTiming(0.3);
-
- button.setPressed(true);
- scheduler.run();
- verify(command).schedule();
- }
-
- @Test
- void booleanSupplierTest() {
- InternalButton button = new InternalButton();
-
- assertFalse(button.getAsBoolean());
- button.setPressed(true);
- assertTrue(button.getAsBoolean());
- }
-}
diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java
index c894cff052..b9adc1344c 100644
--- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java
+++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java
@@ -37,7 +37,7 @@ class NetworkButtonTest extends CommandTestBase {
var button = new NetworkButton(m_inst, "TestTable", "Test");
pub.set(false);
- button.whenPressed(command);
+ button.onTrue(command);
scheduler.run();
verify(command, never()).schedule();
pub.set(true);
diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/TriggerTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/TriggerTest.java
new file mode 100644
index 0000000000..2a9aa6cd29
--- /dev/null
+++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/TriggerTest.java
@@ -0,0 +1,278 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package edu.wpi.first.wpilibj2.command.button;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+import static org.mockito.Mockito.never;
+import static org.mockito.Mockito.verify;
+
+import edu.wpi.first.wpilibj.simulation.SimHooks;
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.CommandScheduler;
+import edu.wpi.first.wpilibj2.command.CommandTestBase;
+import edu.wpi.first.wpilibj2.command.FunctionalCommand;
+import edu.wpi.first.wpilibj2.command.RunCommand;
+import edu.wpi.first.wpilibj2.command.StartEndCommand;
+import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
+import java.util.concurrent.atomic.AtomicBoolean;
+import java.util.concurrent.atomic.AtomicInteger;
+import java.util.function.BooleanSupplier;
+import org.junit.jupiter.api.Test;
+
+class TriggerTest extends CommandTestBase {
+ @Test
+ void onTrueTest() {
+ CommandScheduler scheduler = CommandScheduler.getInstance();
+ AtomicBoolean finished = new AtomicBoolean(false);
+ Command command1 = new WaitUntilCommand(finished::get);
+
+ InternalButton button = new InternalButton();
+ button.setPressed(false);
+ button.onTrue(command1);
+ scheduler.run();
+ assertFalse(command1.isScheduled());
+ button.setPressed(true);
+ scheduler.run();
+ assertTrue(command1.isScheduled());
+ finished.set(true);
+ scheduler.run();
+ assertFalse(command1.isScheduled());
+ }
+
+ @Test
+ void onFalseTest() {
+ CommandScheduler scheduler = CommandScheduler.getInstance();
+ AtomicBoolean finished = new AtomicBoolean(false);
+ Command command1 = new WaitUntilCommand(finished::get);
+
+ InternalButton button = new InternalButton();
+ button.setPressed(true);
+ button.onFalse(command1);
+ scheduler.run();
+ assertFalse(command1.isScheduled());
+ button.setPressed(false);
+ scheduler.run();
+ assertTrue(command1.isScheduled());
+ finished.set(true);
+ scheduler.run();
+ assertFalse(command1.isScheduled());
+ }
+
+ @Test
+ void whileTrueRepeatedlyTest() {
+ CommandScheduler scheduler = CommandScheduler.getInstance();
+ AtomicInteger inits = new AtomicInteger(0);
+ AtomicInteger counter = new AtomicInteger(0);
+ // the repeatedly() here is the point!
+ Command command1 =
+ new FunctionalCommand(
+ inits::incrementAndGet,
+ () -> {},
+ interrupted -> {},
+ () -> counter.incrementAndGet() % 2 == 0)
+ .repeatedly();
+
+ InternalButton button = new InternalButton();
+ button.setPressed(false);
+ button.whileTrue(command1);
+ scheduler.run();
+ assertEquals(0, inits.get());
+ button.setPressed(true);
+ scheduler.run();
+ assertEquals(1, inits.get());
+ scheduler.run();
+ assertEquals(2, inits.get());
+ button.setPressed(false);
+ scheduler.run();
+ assertEquals(2, inits.get());
+ }
+
+ @Test
+ void whileTrueLambdaRunTest() {
+ CommandScheduler scheduler = CommandScheduler.getInstance();
+ AtomicInteger counter = new AtomicInteger(0);
+ // the repeatedly() here is the point!
+ Command command1 = new RunCommand(counter::incrementAndGet);
+
+ InternalButton button = new InternalButton();
+ button.setPressed(false);
+ button.whileTrue(command1);
+ scheduler.run();
+ assertEquals(0, counter.get());
+ button.setPressed(true);
+ scheduler.run();
+ assertEquals(1, counter.get());
+ scheduler.run();
+ assertEquals(2, counter.get());
+ button.setPressed(false);
+ scheduler.run();
+ assertEquals(2, counter.get());
+ }
+
+ @Test
+ void whileTrueOnceTest() {
+ CommandScheduler scheduler = CommandScheduler.getInstance();
+ AtomicInteger startCounter = new AtomicInteger(0);
+ AtomicInteger endCounter = new AtomicInteger(0);
+ Command command1 =
+ new StartEndCommand(startCounter::incrementAndGet, endCounter::incrementAndGet);
+
+ InternalButton button = new InternalButton();
+ button.setPressed(false);
+ button.whileTrue(command1);
+ scheduler.run();
+ assertEquals(0, startCounter.get());
+ assertEquals(0, endCounter.get());
+ button.setPressed(true);
+ scheduler.run();
+ scheduler.run();
+ assertEquals(1, startCounter.get());
+ assertEquals(0, endCounter.get());
+ button.setPressed(false);
+ scheduler.run();
+ assertEquals(1, startCounter.get());
+ assertEquals(1, endCounter.get());
+ }
+
+ @Test
+ void toggleOnTrueTest() {
+ CommandScheduler scheduler = CommandScheduler.getInstance();
+ AtomicInteger startCounter = new AtomicInteger(0);
+ AtomicInteger endCounter = new AtomicInteger(0);
+ Command command1 =
+ new StartEndCommand(startCounter::incrementAndGet, endCounter::incrementAndGet);
+
+ InternalButton button = new InternalButton();
+ button.setPressed(false);
+ button.toggleOnTrue(command1);
+ scheduler.run();
+ assertEquals(0, startCounter.get());
+ assertEquals(0, endCounter.get());
+ button.setPressed(true);
+ scheduler.run();
+ scheduler.run();
+ assertEquals(1, startCounter.get());
+ assertEquals(0, endCounter.get());
+ button.setPressed(false);
+ scheduler.run();
+ assertEquals(1, startCounter.get());
+ assertEquals(0, endCounter.get());
+ button.setPressed(true);
+ scheduler.run();
+ assertEquals(1, startCounter.get());
+ assertEquals(1, endCounter.get());
+ }
+
+ @Test
+ void cancelWhenActiveTest() {
+ CommandScheduler scheduler = CommandScheduler.getInstance();
+ AtomicInteger startCounter = new AtomicInteger(0);
+ AtomicInteger endCounter = new AtomicInteger(0);
+
+ InternalButton button = new InternalButton();
+ Command command1 =
+ new StartEndCommand(startCounter::incrementAndGet, endCounter::incrementAndGet)
+ .until(button.rising());
+
+ button.setPressed(false);
+ command1.schedule();
+ scheduler.run();
+ assertEquals(1, startCounter.get());
+ assertEquals(0, endCounter.get());
+ button.setPressed(true);
+ scheduler.run();
+ assertEquals(1, startCounter.get());
+ assertEquals(1, endCounter.get());
+ scheduler.run();
+ assertEquals(1, startCounter.get());
+ assertEquals(1, endCounter.get());
+ }
+
+ // Binding runnables directly is deprecated -- users should create the command manually
+ @SuppressWarnings("deprecation")
+ @Test
+ void runnableBindingTest() {
+ InternalButton buttonWhenActive = new InternalButton();
+ InternalButton buttonWhileActiveContinuous = new InternalButton();
+ InternalButton buttonWhenInactive = new InternalButton();
+
+ buttonWhenActive.setPressed(false);
+ buttonWhileActiveContinuous.setPressed(true);
+ buttonWhenInactive.setPressed(true);
+
+ AtomicInteger counter = new AtomicInteger(0);
+
+ buttonWhenActive.whenPressed(counter::incrementAndGet);
+ buttonWhileActiveContinuous.whileActiveContinuous(counter::incrementAndGet);
+ buttonWhenInactive.whenInactive(counter::incrementAndGet);
+
+ CommandScheduler scheduler = CommandScheduler.getInstance();
+
+ scheduler.run();
+ buttonWhenActive.setPressed(true);
+ buttonWhenInactive.setPressed(false);
+ scheduler.run();
+
+ assertEquals(counter.get(), 4);
+ }
+
+ @Test
+ void triggerCompositionTest() {
+ InternalButton button1 = new InternalButton();
+ InternalButton button2 = new InternalButton();
+
+ button1.setPressed(true);
+ button2.setPressed(false);
+
+ assertFalse(button1.and(button2).getAsBoolean());
+ assertTrue(button1.or(button2).getAsBoolean());
+ assertFalse(button1.negate().getAsBoolean());
+ assertTrue(button1.and(button2.negate()).getAsBoolean());
+ }
+
+ @Test
+ void triggerCompositionSupplierTest() {
+ InternalButton button1 = new InternalButton();
+ BooleanSupplier booleanSupplier = () -> false;
+
+ button1.setPressed(true);
+
+ assertFalse(button1.and(booleanSupplier).getAsBoolean());
+ assertTrue(button1.or(booleanSupplier).getAsBoolean());
+ }
+
+ @Test
+ void debounceTest() {
+ CommandScheduler scheduler = CommandScheduler.getInstance();
+ MockCommandHolder commandHolder = new MockCommandHolder(true);
+ Command command = commandHolder.getMock();
+
+ InternalButton button = new InternalButton();
+ Trigger debounced = button.debounce(0.1);
+
+ debounced.onTrue(command);
+
+ button.setPressed(true);
+ scheduler.run();
+ verify(command, never()).schedule();
+
+ SimHooks.stepTiming(0.3);
+
+ button.setPressed(true);
+ scheduler.run();
+ verify(command).schedule();
+ }
+
+ @Test
+ void booleanSupplierTest() {
+ InternalButton button = new InternalButton();
+
+ assertFalse(button.getAsBoolean());
+ button.setPressed(true);
+ assertTrue(button.getAsBoolean());
+ }
+}
diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/POVButtonTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/POVButtonTest.cpp
index 5f6e733f15..bcb7dece94 100644
--- a/wpilibNewCommands/src/test/native/cpp/frc2/command/POVButtonTest.cpp
+++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/POVButtonTest.cpp
@@ -26,7 +26,7 @@ TEST_F(POVButtonTest, SetPOV) {
WaitUntilCommand command([&finished] { return finished; });
frc::Joystick joy(1);
- POVButton(&joy, 90).WhenPressed(&command);
+ POVButton(&joy, 90).OnTrue(&command);
scheduler.Run();
EXPECT_FALSE(scheduler.IsScheduled(&command));
diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/button/NetworkButtonTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/button/NetworkButtonTest.cpp
index 95a7eee628..51da1d2939 100644
--- a/wpilibNewCommands/src/test/native/cpp/frc2/command/button/NetworkButtonTest.cpp
+++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/button/NetworkButtonTest.cpp
@@ -32,7 +32,7 @@ TEST_F(NetworkButtonTest, SetNetworkButton) {
WaitUntilCommand command([&finished] { return finished; });
- NetworkButton(inst, "TestTable", "Test").WhenActive(&command);
+ NetworkButton(inst, "TestTable", "Test").OnTrue(&command);
scheduler.Run();
EXPECT_FALSE(scheduler.IsScheduled(&command));
pub.Set(true);
diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/button/ButtonTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/button/TriggerTest.cpp
similarity index 58%
rename from wpilibNewCommands/src/test/native/cpp/frc2/command/button/ButtonTest.cpp
rename to wpilibNewCommands/src/test/native/cpp/frc2/command/button/TriggerTest.cpp
index db4276df79..6c38900d30 100644
--- a/wpilibNewCommands/src/test/native/cpp/frc2/command/button/ButtonTest.cpp
+++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/button/TriggerTest.cpp
@@ -5,23 +5,25 @@
#include
#include "../CommandTestBase.h"
+#include "frc2/command/CommandPtr.h"
#include "frc2/command/CommandScheduler.h"
+#include "frc2/command/Commands.h"
#include "frc2/command/RunCommand.h"
#include "frc2/command/WaitUntilCommand.h"
#include "frc2/command/button/Trigger.h"
#include "gtest/gtest.h"
using namespace frc2;
-class ButtonTest : public CommandTestBase {};
+class TriggerTest : public CommandTestBase {};
-TEST_F(ButtonTest, WhenPressed) {
+TEST_F(TriggerTest, OnTrue) {
auto& scheduler = CommandScheduler::GetInstance();
bool finished = false;
bool pressed = false;
WaitUntilCommand command([&finished] { return finished; });
- Trigger([&pressed] { return pressed; }).WhenActive(&command);
+ Trigger([&pressed] { return pressed; }).OnTrue(&command);
scheduler.Run();
EXPECT_FALSE(scheduler.IsScheduled(&command));
pressed = true;
@@ -32,14 +34,14 @@ TEST_F(ButtonTest, WhenPressed) {
EXPECT_FALSE(scheduler.IsScheduled(&command));
}
-TEST_F(ButtonTest, WhenReleased) {
+TEST_F(TriggerTest, OnFalse) {
auto& scheduler = CommandScheduler::GetInstance();
bool finished = false;
bool pressed = false;
WaitUntilCommand command([&finished] { return finished; });
pressed = true;
- Trigger([&pressed] { return pressed; }).WhenInactive(&command);
+ Trigger([&pressed] { return pressed; }).OnFalse(&command);
scheduler.Run();
EXPECT_FALSE(scheduler.IsScheduled(&command));
pressed = false;
@@ -50,87 +52,111 @@ TEST_F(ButtonTest, WhenReleased) {
EXPECT_FALSE(scheduler.IsScheduled(&command));
}
-TEST_F(ButtonTest, WhileHeld) {
+TEST_F(TriggerTest, WhileTrueRepeatedly) {
auto& scheduler = CommandScheduler::GetInstance();
- bool finished = false;
+ int inits = 0;
+ int counter = 0;
bool pressed = false;
- WaitUntilCommand command([&finished] { return finished; });
+ CommandPtr command =
+ FunctionalCommand([&inits] { inits++; }, [] {}, [](bool interrupted) {},
+ [&counter] { return ++counter % 2 == 0; })
+ .Repeatedly();
pressed = false;
- Trigger([&pressed] { return pressed; }).WhileActiveContinous(&command);
+ Trigger([&pressed] { return pressed; }).WhileTrue(std::move(command));
scheduler.Run();
- EXPECT_FALSE(scheduler.IsScheduled(&command));
+ EXPECT_EQ(0, inits);
pressed = true;
scheduler.Run();
- EXPECT_TRUE(scheduler.IsScheduled(&command));
- finished = true;
+ EXPECT_EQ(1, inits);
scheduler.Run();
- finished = false;
- scheduler.Run();
- EXPECT_TRUE(scheduler.IsScheduled(&command));
+ EXPECT_EQ(2, inits);
pressed = false;
scheduler.Run();
- EXPECT_FALSE(scheduler.IsScheduled(&command));
+ EXPECT_EQ(2, inits);
}
-TEST_F(ButtonTest, WhenHeld) {
+TEST_F(TriggerTest, WhileTrueLambdaRun) {
auto& scheduler = CommandScheduler::GetInstance();
- bool finished = false;
+ int counter = 0;
bool pressed = false;
- WaitUntilCommand command([&finished] { return finished; });
+ CommandPtr command = cmd::Run([&counter] { counter++; });
pressed = false;
- Trigger([&pressed] { return pressed; }).WhileActiveOnce(&command);
+ Trigger([&pressed] { return pressed; }).WhileTrue(std::move(command));
scheduler.Run();
- EXPECT_FALSE(scheduler.IsScheduled(&command));
+ EXPECT_EQ(0, counter);
pressed = true;
scheduler.Run();
- EXPECT_TRUE(scheduler.IsScheduled(&command));
- finished = true;
- scheduler.Run();
- finished = false;
- scheduler.Run();
- EXPECT_FALSE(scheduler.IsScheduled(&command));
-
- pressed = false;
- Trigger([&pressed] { return pressed; }).WhileActiveOnce(&command);
- pressed = true;
scheduler.Run();
+ EXPECT_EQ(2, counter);
pressed = false;
scheduler.Run();
- EXPECT_FALSE(scheduler.IsScheduled(&command));
+ EXPECT_EQ(2, counter);
}
-TEST_F(ButtonTest, ToggleWhenPressed) {
+TEST_F(TriggerTest, WhenTrueOnce) {
auto& scheduler = CommandScheduler::GetInstance();
- bool finished = false;
+ int startCounter = 0;
+ int endCounter = 0;
bool pressed = false;
- WaitUntilCommand command([&finished] { return finished; });
+
+ CommandPtr command = cmd::StartEnd([&startCounter] { startCounter++; },
+ [&endCounter] { endCounter++; });
pressed = false;
- Trigger([&pressed] { return pressed; }).ToggleWhenActive(&command);
+ Trigger([&pressed] { return pressed; }).WhileTrue(std::move(command));
scheduler.Run();
- EXPECT_FALSE(scheduler.IsScheduled(&command));
+ EXPECT_EQ(0, startCounter);
+ EXPECT_EQ(0, endCounter);
pressed = true;
scheduler.Run();
- EXPECT_TRUE(scheduler.IsScheduled(&command));
+ scheduler.Run();
+ EXPECT_EQ(1, startCounter);
+ EXPECT_EQ(0, endCounter);
pressed = false;
scheduler.Run();
- pressed = true;
- scheduler.Run();
- EXPECT_FALSE(scheduler.IsScheduled(&command));
+ EXPECT_EQ(1, startCounter);
+ EXPECT_EQ(1, endCounter);
}
-TEST_F(ButtonTest, And) {
+TEST_F(TriggerTest, ToggleOnTrue) {
+ auto& scheduler = CommandScheduler::GetInstance();
+ bool pressed = false;
+ int startCounter = 0;
+ int endCounter = 0;
+ CommandPtr command = cmd::StartEnd([&startCounter] { startCounter++; },
+ [&endCounter] { endCounter++; });
+
+ Trigger([&pressed] { return pressed; }).ToggleOnTrue(std::move(command));
+ scheduler.Run();
+ EXPECT_EQ(0, startCounter);
+ EXPECT_EQ(0, endCounter);
+ pressed = true;
+ scheduler.Run();
+ scheduler.Run();
+ EXPECT_EQ(1, startCounter);
+ EXPECT_EQ(0, endCounter);
+ pressed = false;
+ scheduler.Run();
+ EXPECT_EQ(1, startCounter);
+ EXPECT_EQ(0, endCounter);
+ pressed = true;
+ scheduler.Run();
+ EXPECT_EQ(1, startCounter);
+ EXPECT_EQ(1, endCounter);
+}
+
+TEST_F(TriggerTest, And) {
auto& scheduler = CommandScheduler::GetInstance();
bool finished = false;
bool pressed1 = false;
bool pressed2 = false;
WaitUntilCommand command([&finished] { return finished; });
- (Trigger([&pressed1] { return pressed1; }) && Trigger([&pressed2] {
+ (Trigger([&pressed1] { return pressed1; }) && ([&pressed2] {
return pressed2;
- })).WhenActive(&command);
+ })).OnTrue(&command);
pressed1 = true;
scheduler.Run();
EXPECT_FALSE(scheduler.IsScheduled(&command));
@@ -139,7 +165,7 @@ TEST_F(ButtonTest, And) {
EXPECT_TRUE(scheduler.IsScheduled(&command));
}
-TEST_F(ButtonTest, Or) {
+TEST_F(TriggerTest, Or) {
auto& scheduler = CommandScheduler::GetInstance();
bool finished = false;
bool pressed1 = false;
@@ -147,30 +173,30 @@ TEST_F(ButtonTest, Or) {
WaitUntilCommand command1([&finished] { return finished; });
WaitUntilCommand command2([&finished] { return finished; });
- (Trigger([&pressed1] { return pressed1; }) || Trigger([&pressed2] {
+ (Trigger([&pressed1] { return pressed1; }) || ([&pressed2] {
return pressed2;
- })).WhenActive(&command1);
+ })).OnTrue(&command1);
pressed1 = true;
scheduler.Run();
EXPECT_TRUE(scheduler.IsScheduled(&command1));
pressed1 = false;
- (Trigger([&pressed1] { return pressed1; }) || Trigger([&pressed2] {
+ (Trigger([&pressed1] { return pressed1; }) || ([&pressed2] {
return pressed2;
- })).WhenActive(&command2);
+ })).OnTrue(&command2);
pressed2 = true;
scheduler.Run();
EXPECT_TRUE(scheduler.IsScheduled(&command2));
}
-TEST_F(ButtonTest, Negate) {
+TEST_F(TriggerTest, Negate) {
auto& scheduler = CommandScheduler::GetInstance();
bool finished = false;
bool pressed = true;
WaitUntilCommand command([&finished] { return finished; });
- (!Trigger([&pressed] { return pressed; })).WhenActive(&command);
+ (!Trigger([&pressed] { return pressed; })).OnTrue(&command);
scheduler.Run();
EXPECT_FALSE(scheduler.IsScheduled(&command));
pressed = false;
@@ -178,7 +204,9 @@ TEST_F(ButtonTest, Negate) {
EXPECT_TRUE(scheduler.IsScheduled(&command));
}
-TEST_F(ButtonTest, RValueButton) {
+// this type of binding is deprecated and identical to OnTrue
+WPI_IGNORE_DEPRECATED
+TEST_F(TriggerTest, RValueTrigger) {
auto& scheduler = CommandScheduler::GetInstance();
int counter = 0;
bool pressed = false;
@@ -192,13 +220,14 @@ TEST_F(ButtonTest, RValueButton) {
scheduler.Run();
EXPECT_EQ(counter, 1);
}
+WPI_UNIGNORE_DEPRECATED
-TEST_F(ButtonTest, Debounce) {
+TEST_F(TriggerTest, Debounce) {
auto& scheduler = CommandScheduler::GetInstance();
bool pressed = false;
RunCommand command([] {});
- Trigger([&pressed] { return pressed; }).Debounce(100_ms).WhenActive(&command);
+ Trigger([&pressed] { return pressed; }).Debounce(100_ms).OnTrue(&command);
pressed = true;
scheduler.Run();
EXPECT_FALSE(scheduler.IsScheduled(&command));
diff --git a/wpilibc/src/main/native/include/frc/event/BooleanEvent.h b/wpilibc/src/main/native/include/frc/event/BooleanEvent.h
index 513d57842b..d550543e47 100644
--- a/wpilibc/src/main/native/include/frc/event/BooleanEvent.h
+++ b/wpilibc/src/main/native/include/frc/event/BooleanEvent.h
@@ -64,8 +64,7 @@ class BooleanEvent {
* second.
* @return an instance of the subclass.
*/
- template >>
+ template
T CastTo(std::function)> ctor =
[](EventLoop* loop, std::function condition) {
return T(loop, condition);
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
index 158945e642..1593f225ff 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
@@ -5,6 +5,9 @@
#include "RobotContainer.h"
#include
+#include
+#include
+#include
#include
#include
@@ -28,31 +31,31 @@ void RobotContainer::ConfigureButtonBindings() {
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
- .WhenPressed(
+ .OnTrue(frc2::cmd::RunOnce(
[this] {
m_arm.SetGoal(2_rad);
m_arm.Enable();
},
- {&m_arm});
+ {&m_arm}));
// Move the arm to neutral position when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
- .WhenPressed(
+ .OnTrue(frc2::cmd::RunOnce(
[this] {
m_arm.SetGoal(ArmConstants::kArmOffset);
m_arm.Enable();
},
- {&m_arm});
+ {&m_arm}));
// Disable the arm controller when Y is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kY)
- .WhenPressed([this] { m_arm.Disable(); }, {&m_arm});
+ .OnTrue(frc2::cmd::RunOnce([this] { m_arm.Disable(); }, {&m_arm}));
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
- .WhenPressed([this] { m_drive.SetMaxOutput(0.5); })
- .WhenReleased([this] { m_drive.SetMaxOutput(1); });
+ .OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }))
+ .OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }));
}
void RobotContainer::DisablePIDSubsystems() {
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h
index 782207b355..5d2c148227 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h
@@ -7,13 +7,6 @@
#include
#include
#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
#include "Constants.h"
#include "subsystems/ArmSubsystem.h"
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
index 1f6a138bc5..f3ef220938 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
@@ -5,6 +5,9 @@
#include "RobotContainer.h"
#include
+#include
+#include
+#include
#include
#include
@@ -28,18 +31,18 @@ void RobotContainer::ConfigureButtonBindings() {
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
- .WhenPressed([this] { m_arm.SetGoal(2_rad); }, {&m_arm});
+ .OnTrue(frc2::cmd::RunOnce([this] { m_arm.SetGoal(2_rad); }, {&m_arm}));
// Move the arm to neutral position when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
- .WhenPressed([this] { m_arm.SetGoal(ArmConstants::kArmOffset); },
- {&m_arm});
+ .OnTrue(frc2::cmd::RunOnce(
+ [this] { m_arm.SetGoal(ArmConstants::kArmOffset); }, {&m_arm}));
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
- .WhenPressed([this] { m_drive.SetMaxOutput(0.5); })
- .WhenReleased([this] { m_drive.SetMaxOutput(1); });
+ .OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }))
+ .OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }));
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h
index 5aba4706d7..275230eb36 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h
@@ -7,13 +7,6 @@
#include
#include
#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
#include "Constants.h"
#include "subsystems/ArmSubsystem.h"
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
index bc940cd319..7dc1ebf811 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
@@ -5,6 +5,7 @@
#include "RobotContainer.h"
#include
+#include
#include
#include "commands/DriveDistanceProfiled.h"
@@ -16,7 +17,7 @@ RobotContainer::RobotContainer() {
ConfigureButtonBindings();
// Set up default drive command
- m_drive.SetDefaultCommand(frc2::RunCommand(
+ m_drive.SetDefaultCommand(frc2::cmd::Run(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
@@ -30,18 +31,18 @@ void RobotContainer::ConfigureButtonBindings() {
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
- .WhenPressed(&m_driveHalfSpeed)
- .WhenReleased(&m_driveFullSpeed);
+ .OnTrue(&m_driveHalfSpeed)
+ .OnFalse(&m_driveFullSpeed);
// Drive forward by 3 meters when the 'A' button is pressed, with a timeout of
// 10 seconds
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
- .WhenPressed(DriveDistanceProfiled(3_m, &m_drive).WithTimeout(10_s));
+ .OnTrue(DriveDistanceProfiled(3_m, &m_drive).WithTimeout(10_s));
// Do the same thing as above when the 'B' button is pressed, but defined
// inline
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
- .WhenPressed(
+ .OnTrue(
frc2::TrapezoidProfileCommand(
frc::TrapezoidProfile(
// Limit the max acceleration and velocity
@@ -54,7 +55,9 @@ void RobotContainer::ConfigureButtonBindings() {
},
// Require the drive
{&m_drive})
- .BeforeStarting([this]() { m_drive.ResetEncoders(); })
+ .ToPtr()
+ .BeforeStarting(
+ frc2::cmd::RunOnce([this]() { m_drive.ResetEncoders(); }, {}))
.WithTimeout(10_s));
}
diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp
index 9743a4df58..342209d4e6 100644
--- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp
@@ -27,22 +27,22 @@ void RobotContainer::ConfigureButtonBindings() {
// Spin up the shooter when the 'A' button is pressed
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
- .WhenPressed(&m_spinUpShooter);
+ .OnTrue(&m_spinUpShooter);
// Turn off the shooter when the 'B' button is pressed
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
- .WhenPressed(&m_stopShooter);
+ .OnTrue(&m_stopShooter);
// Shoot when the 'X' button is held
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kX)
- .WhenPressed(&m_shoot)
- .WhenReleased(&m_stopFeeder);
+ .OnTrue(&m_shoot)
+ .OnFalse(&m_stopFeeder);
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
- .WhenPressed(&m_driveHalfSpeed)
- .WhenReleased(&m_driveFullSpeed);
+ .OnTrue(&m_driveHalfSpeed)
+ .OnFalse(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp
index 37eb460d5a..f122cbe11e 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp
@@ -32,20 +32,20 @@ RobotContainer::RobotContainer()
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
- frc2::JoystickButton(&m_joy, 5).WhenPressed(
- SetElevatorSetpoint(0.25, m_elevator));
- frc2::JoystickButton(&m_joy, 6).WhenPressed(CloseClaw(m_claw));
- frc2::JoystickButton(&m_joy, 7).WhenPressed(
- SetElevatorSetpoint(0.0, m_elevator));
- frc2::JoystickButton(&m_joy, 8).WhenPressed(OpenClaw(m_claw));
- frc2::JoystickButton(&m_joy, 9).WhenPressed(
- Autonomous(m_claw, m_wrist, m_elevator, m_drivetrain));
+ frc2::JoystickButton(&m_joy, 5).OnTrue(
+ SetElevatorSetpoint(0.25, m_elevator).ToPtr());
+ frc2::JoystickButton(&m_joy, 6).OnTrue(CloseClaw(m_claw).ToPtr());
+ frc2::JoystickButton(&m_joy, 7).OnTrue(
+ SetElevatorSetpoint(0.0, m_elevator).ToPtr());
+ frc2::JoystickButton(&m_joy, 8).OnTrue(OpenClaw(m_claw).ToPtr());
+ frc2::JoystickButton(&m_joy, 9).OnTrue(
+ Autonomous(m_claw, m_wrist, m_elevator, m_drivetrain).ToPtr());
frc2::JoystickButton(&m_joy, 10)
- .WhenPressed(Pickup(m_claw, m_wrist, m_elevator));
+ .OnTrue(Pickup(m_claw, m_wrist, m_elevator).ToPtr());
frc2::JoystickButton(&m_joy, 11)
- .WhenPressed(Place(m_claw, m_wrist, m_elevator));
+ .OnTrue(Place(m_claw, m_wrist, m_elevator).ToPtr());
frc2::JoystickButton(&m_joy, 12)
- .WhenPressed(PrepareToPickup(m_claw, m_wrist, m_elevator));
+ .OnTrue(PrepareToPickup(m_claw, m_wrist, m_elevator).ToPtr());
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
index 6f5911e2a9..739bed2319 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
@@ -5,6 +5,7 @@
#include "RobotContainer.h"
#include
+#include
#include
#include
#include
@@ -32,33 +33,35 @@ void RobotContainer::ConfigureButtonBindings() {
// Stabilize robot to drive straight with gyro when L1 is held
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kL1)
- .WhenHeld(frc2::PIDCommand{
- frc2::PIDController{dc::kStabilizationP, dc::kStabilizationI,
- dc::kStabilizationD},
- // Close the loop on the turn rate
- [this] { return m_drive.GetTurnRate(); },
- // Setpoint is 0
- 0,
- // Pipe the output to the turning controls
- [this](double output) {
- m_drive.ArcadeDrive(m_driverController.GetLeftY(), output);
- },
- // Require the robot drive
- {&m_drive}});
+ .WhileTrue(
+ frc2::PIDCommand(
+ frc2::PIDController{dc::kStabilizationP, dc::kStabilizationI,
+ dc::kStabilizationD},
+ // Close the loop on the turn rate
+ [this] { return m_drive.GetTurnRate(); },
+ // Setpoint is 0
+ 0,
+ // Pipe the output to the turning controls
+ [this](double output) {
+ m_drive.ArcadeDrive(m_driverController.GetLeftY(), output);
+ },
+ // Require the robot drive
+ {&m_drive})
+ .ToPtr());
// Turn to 90 degrees when the 'Cross' button is pressed
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kCross)
- .WhenPressed(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
+ .OnTrue(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
// Turn to -90 degrees with a profile when the 'Square' button is pressed,
// with a 5 second timeout
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kSquare)
- .WhenPressed(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
+ .OnTrue(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
// While holding R1, drive at half speed
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kR1)
- .WhenPressed(frc2::InstantCommand{[this] { m_drive.SetMaxOutput(0.5); }})
- .WhenReleased(frc2::InstantCommand{[this] { m_drive.SetMaxOutput(1); }});
+ .OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {}))
+ .OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }, {}));
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
index 8fae7d2a7e..dd46d183eb 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
@@ -34,14 +34,14 @@ void RobotContainer::ConfigureButtonBindings() {
// Grab the hatch when the 'Circle' button is pressed.
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kCircle)
- .WhenPressed(&m_grabHatch);
+ .OnTrue(&m_grabHatch);
// Release the hatch when the 'Square' button is pressed.
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kSquare)
- .WhenPressed(&m_releaseHatch);
+ .OnTrue(&m_releaseHatch);
// While holding R1, drive at half speed
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kR1)
- .WhenPressed(&m_driveHalfSpeed)
- .WhenReleased(&m_driveFullSpeed);
+ .OnTrue(&m_driveHalfSpeed)
+ .OnFalse(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
index 6f8c5a60b5..379afcb7a2 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
@@ -41,14 +41,14 @@ void RobotContainer::ConfigureButtonBindings() {
// Grab the hatch when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
- .WhenPressed(new GrabHatch(&m_hatch));
+ .OnTrue(GrabHatch(&m_hatch).ToPtr());
// Release the hatch when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
- .WhenPressed(new ReleaseHatch(&m_hatch));
+ .OnTrue(ReleaseHatch(&m_hatch).ToPtr());
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
- .WhenHeld(new HalveDriveSpeed(&m_drive));
+ .WhileTrue(HalveDriveSpeed(&m_drive).ToPtr());
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp
index 3180caf55d..182171f7ec 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp
@@ -43,8 +43,8 @@ void RobotContainer::ConfigureButtonBindings() {
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
- .WhenPressed(&m_driveHalfSpeed)
- .WhenReleased(&m_driveFullSpeed);
+ .OnTrue(&m_driveHalfSpeed)
+ .OnFalse(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp
index 3d884e693c..fd595f394d 100644
--- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp
@@ -39,8 +39,8 @@ void RobotContainer::ConfigureButtonBindings() {
// While holding the shoulder button, drive at half speed
frc2::JoystickButton{&m_driverController, 6}
- .WhenPressed(&m_driveHalfSpeed)
- .WhenReleased(&m_driveFullSpeed);
+ .OnTrue(&m_driveHalfSpeed)
+ .OnFalse(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp
index 3cbad01f95..d09162cb2a 100644
--- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp
@@ -5,7 +5,7 @@
#include "RobotContainer.h"
#include
-#include
+#include
#include
#include "commands/TeleopArcadeDrive.h"
@@ -22,8 +22,8 @@ void RobotContainer::ConfigureButtonBindings() {
[this] { return m_controller.GetRawAxis(2); }));
// Example of how to use the onboard IO
- m_onboardButtonA.WhenPressed(frc2::PrintCommand("Button A Pressed"))
- .WhenReleased(frc2::PrintCommand("Button A Released"));
+ m_onboardButtonA.OnTrue(frc2::cmd::Print("Button A Pressed"))
+ .OnFalse(frc2::cmd::Print("Button A Released"));
// Setup SmartDashboard options.
m_chooser.SetDefaultOption("Auto Routine Distance", &m_autoDistance);
diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.h
index 821542cfe6..78da957d9e 100644
--- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.h
+++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.h
@@ -7,6 +7,7 @@
#include
#include
#include
+#include
#include
#include "Constants.h"
diff --git a/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/RobotContainer.cpp
index 0c2e79cb72..e54c42f24b 100644
--- a/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/RobotContainer.cpp
@@ -46,14 +46,14 @@ void RobotContainer::ConfigureButtonBindings() {
// Run instant command 1 when the 'A' button is pressed
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
- .WhenPressed(&m_instantCommand1);
+ .OnTrue(&m_instantCommand1);
// Run instant command 2 when the 'X' button is pressed
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kX)
- .WhenPressed(&m_instantCommand2);
+ .OnTrue(&m_instantCommand2);
// Run instant command 3 when the 'Y' button is held; release early to
// interrupt
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kY)
- .WhenHeld(&m_waitCommand);
+ .OnTrue(&m_waitCommand);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp
index e8f31282cb..c757373fcc 100644
--- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp
@@ -53,8 +53,8 @@ void RobotContainer::ConfigureButtonBindings() {
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
- .WhenPressed(&m_driveHalfSpeed)
- .WhenReleased(&m_driveFullSpeed);
+ .OnTrue(&m_driveHalfSpeed)
+ .OnFalse(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java
index 33d76aeaf3..742a7a8b30 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/event/BooleanEvent.java
@@ -178,7 +178,7 @@ public class BooleanEvent implements BooleanSupplier {
* @param the subclass type
* @return an instance of the subclass.
*/
- public T castTo(BiFunction ctor) {
+ public T castTo(BiFunction ctor) {
return ctor.apply(m_loop, m_signal);
}
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java
index 4717d51709..c2c401d86e 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java
@@ -55,29 +55,32 @@ public class RobotContainer {
private void configureButtonBindings() {
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
new JoystickButton(m_driverController, Button.kA.value)
- .whenPressed(
- () -> {
- m_robotArm.setGoal(2);
- m_robotArm.enable();
- },
- m_robotArm);
+ .onTrue(
+ new InstantCommand(
+ () -> {
+ m_robotArm.setGoal(2);
+ m_robotArm.enable();
+ },
+ m_robotArm));
// Move the arm to neutral position when the 'B' button is pressed.
new JoystickButton(m_driverController, Button.kB.value)
- .whenPressed(
- () -> {
- m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads);
- m_robotArm.enable();
- },
- m_robotArm);
+ .onTrue(
+ new InstantCommand(
+ () -> {
+ m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads);
+ m_robotArm.enable();
+ },
+ m_robotArm));
// Disable the arm controller when Y is pressed.
- new JoystickButton(m_driverController, Button.kY.value).whenPressed(m_robotArm::disable);
+ new JoystickButton(m_driverController, Button.kY.value)
+ .onTrue(new InstantCommand(m_robotArm::disable));
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kRightBumper.value)
- .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
- .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+ .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+ .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java
index 7ea79995b3..bd19e4e853 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java
@@ -55,16 +55,18 @@ public class RobotContainer {
private void configureButtonBindings() {
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
new JoystickButton(m_driverController, Button.kA.value)
- .whenPressed(() -> m_robotArm.setGoal(2), m_robotArm);
+ .onTrue(new InstantCommand(() -> m_robotArm.setGoal(2), m_robotArm));
// Move the arm to neutral position when the 'B' button is pressed.
new JoystickButton(m_driverController, Button.kB.value)
- .whenPressed(() -> m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads), m_robotArm);
+ .onTrue(
+ new InstantCommand(
+ () -> m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads), m_robotArm));
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kRightBumper.value)
- .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
- .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+ .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+ .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java
index cc39207569..edadde41b5 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java
@@ -57,11 +57,11 @@ public class RobotContainer {
private void configureButtonBindings() {
// Drive forward by 3 meters when the 'A' button is pressed, with a timeout of 10 seconds
new JoystickButton(m_driverController, Button.kA.value)
- .whenPressed(new DriveDistanceProfiled(3, m_robotDrive).withTimeout(10));
+ .onTrue(new DriveDistanceProfiled(3, m_robotDrive).withTimeout(10));
// Do the same thing as above when the 'B' button is pressed, but defined inline
new JoystickButton(m_driverController, Button.kB.value)
- .whenPressed(
+ .onTrue(
new TrapezoidProfileCommand(
new TrapezoidProfile(
// Limit the max acceleration and velocity
@@ -79,8 +79,8 @@ public class RobotContainer {
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kRightBumper.value)
- .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
- .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+ .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+ .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java
index 1f00dd9ce8..30a4a1aa26 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java
@@ -80,15 +80,15 @@ public class RobotContainer {
private void configureButtonBindings() {
// Spin up the shooter when the 'A' button is pressed
new JoystickButton(m_driverController, Button.kA.value)
- .whenPressed(new InstantCommand(m_shooter::enable, m_shooter));
+ .onTrue(new InstantCommand(m_shooter::enable, m_shooter));
// Turn off the shooter when the 'B' button is pressed
new JoystickButton(m_driverController, Button.kB.value)
- .whenPressed(new InstantCommand(m_shooter::disable, m_shooter));
+ .onTrue(new InstantCommand(m_shooter::disable, m_shooter));
// Run the feeder when the 'X' button is held, but only if the shooter is at speed
new JoystickButton(m_driverController, Button.kX.value)
- .whenPressed(
+ .onTrue(
new ConditionalCommand(
// Run the feeder
new InstantCommand(m_shooter::runFeeder, m_shooter),
@@ -97,12 +97,12 @@ public class RobotContainer {
// Determine which of the above to do based on whether the shooter has reached the
// desired speed
m_shooter::atSetpoint))
- .whenReleased(new InstantCommand(m_shooter::stopFeeder, m_shooter));
+ .onFalse(new InstantCommand(m_shooter::stopFeeder, m_shooter));
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kRightBumper.value)
- .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
- .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+ .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+ .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java
index e4c7412c36..f898181a67 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java
@@ -88,15 +88,15 @@ public class RobotContainer {
final JoystickButton r1 = new JoystickButton(m_joystick, 12);
// Connect the buttons to commands
- dpadUp.whenPressed(new SetElevatorSetpoint(0.25, m_elevator));
- dpadDown.whenPressed(new SetElevatorSetpoint(0.0, m_elevator));
- dpadRight.whenPressed(new CloseClaw(m_claw));
- dpadLeft.whenPressed(new OpenClaw(m_claw));
+ dpadUp.onTrue(new SetElevatorSetpoint(0.25, m_elevator));
+ dpadDown.onTrue(new SetElevatorSetpoint(0.0, m_elevator));
+ dpadRight.onTrue(new CloseClaw(m_claw));
+ dpadLeft.onTrue(new OpenClaw(m_claw));
- r1.whenPressed(new PrepareToPickup(m_claw, m_wrist, m_elevator));
- r2.whenPressed(new Pickup(m_claw, m_wrist, m_elevator));
- l1.whenPressed(new Place(m_claw, m_wrist, m_elevator));
- l2.whenPressed(new Autonomous(m_drivetrain, m_claw, m_wrist, m_elevator));
+ r1.onTrue(new PrepareToPickup(m_claw, m_wrist, m_elevator));
+ r2.onTrue(new Pickup(m_claw, m_wrist, m_elevator));
+ l1.onTrue(new Place(m_claw, m_wrist, m_elevator));
+ l2.onTrue(new Autonomous(m_drivetrain, m_claw, m_wrist, m_elevator));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java
index b70f5bf649..a06cd76f18 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java
@@ -58,12 +58,12 @@ public class RobotContainer {
private void configureButtonBindings() {
// Drive at half speed when the right bumper is held
new JoystickButton(m_driverController, Button.kR1.value)
- .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
- .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+ .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+ .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
// Stabilize robot to drive straight with gyro when left bumper is held
new JoystickButton(m_driverController, Button.kL1.value)
- .whenHeld(
+ .whileTrue(
new PIDCommand(
new PIDController(
DriveConstants.kStabilizationP,
@@ -80,11 +80,11 @@ public class RobotContainer {
// Turn to 90 degrees when the 'X' button is pressed, with a 5 second timeout
new JoystickButton(m_driverController, Button.kCross.value)
- .whenPressed(new TurnToAngle(90, m_robotDrive).withTimeout(5));
+ .onTrue(new TurnToAngle(90, m_robotDrive).withTimeout(5));
// Turn to -90 degrees with a profile when the Circle button is pressed, with a 5 second timeout
new JoystickButton(m_driverController, Button.kCircle.value)
- .whenPressed(new TurnToAngleProfiled(-90, m_robotDrive).withTimeout(5));
+ .onTrue(new TurnToAngleProfiled(-90, m_robotDrive).withTimeout(5));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java
index cda9e26c04..ba7a889895 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java
@@ -89,14 +89,14 @@ public class RobotContainer {
private void configureButtonBindings() {
// Grab the hatch when the Circle button is pressed.
new JoystickButton(m_driverController, Button.kCircle.value)
- .whenPressed(new InstantCommand(m_hatchSubsystem::grabHatch, m_hatchSubsystem));
+ .onTrue(new InstantCommand(m_hatchSubsystem::grabHatch, m_hatchSubsystem));
// Release the hatch when the Square button is pressed.
new JoystickButton(m_driverController, Button.kSquare.value)
- .whenPressed(new InstantCommand(m_hatchSubsystem::releaseHatch, m_hatchSubsystem));
+ .onTrue(new InstantCommand(m_hatchSubsystem::releaseHatch, m_hatchSubsystem));
// While holding R1, drive at half speed
new JoystickButton(m_driverController, Button.kR1.value)
- .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
- .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+ .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+ .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java
index 1f1024f04c..f8e3362286 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java
@@ -78,14 +78,13 @@ public class RobotContainer {
*/
private void configureButtonBindings() {
// Grab the hatch when the 'A' button is pressed.
- new JoystickButton(m_driverController, Button.kA.value)
- .whenPressed(new GrabHatch(m_hatchSubsystem));
+ new JoystickButton(m_driverController, Button.kA.value).onTrue(new GrabHatch(m_hatchSubsystem));
// Release the hatch when the 'B' button is pressed.
new JoystickButton(m_driverController, Button.kB.value)
- .whenPressed(new ReleaseHatch(m_hatchSubsystem));
+ .onTrue(new ReleaseHatch(m_hatchSubsystem));
// While holding the shoulder button, drive at half speed
new JoystickButton(m_driverController, Button.kRightBumper.value)
- .whenHeld(new HalveDriveSpeed(m_robotDrive));
+ .whileTrue(new HalveDriveSpeed(m_robotDrive));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java
index 0d36a9400c..29a311ea16 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java
@@ -19,6 +19,7 @@ import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.DriveCo
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.OIConstants;
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.MecanumControllerCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
@@ -66,8 +67,8 @@ public class RobotContainer {
private void configureButtonBindings() {
// Drive at half speed when the right bumper is held
new JoystickButton(m_driverController, Button.kRightBumper.value)
- .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
- .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+ .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+ .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java
index 5df8d2f584..3192bb162d 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java
@@ -22,6 +22,7 @@ import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.DriveConstants;
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.OIConstants;
import edu.wpi.first.wpilibj.examples.ramsetecommand.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RamseteCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
@@ -66,8 +67,8 @@ public class RobotContainer {
private void configureButtonBindings() {
// Drive at half speed when the right bumper is held
new JoystickButton(m_driverController, Button.kRightBumper.value)
- .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
- .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+ .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+ .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/RobotContainer.java
index 8ad7bc3564..bc07ebb676 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/RobotContainer.java
@@ -17,7 +17,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.PrintCommand;
-import edu.wpi.first.wpilibj2.command.button.Button;
+import edu.wpi.first.wpilibj2.command.button.Trigger;
/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -65,10 +65,10 @@ public class RobotContainer {
m_drivetrain.setDefaultCommand(getArcadeDriveCommand());
// Example of how to use the onboard IO
- Button onboardButtonA = new Button(m_onboardIO::getButtonAPressed);
+ Trigger onboardButtonA = new Trigger(m_onboardIO::getButtonAPressed);
onboardButtonA
- .whenActive(new PrintCommand("Button A Pressed"))
- .whenInactive(new PrintCommand("Button A Released"));
+ .onTrue(new PrintCommand("Button A Pressed"))
+ .onFalse(new PrintCommand("Button A Released"));
// Setup SmartDashboard options
m_chooser.setDefaultOption("Auto Routine Distance", new AutonomousDistance(m_drivetrain));
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/RobotContainer.java
index c7986009f9..fcb467cb1a 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/RobotContainer.java
@@ -70,11 +70,11 @@ public class RobotContainer {
*/
private void configureButtonBindings() {
// Run instant command 1 when the 'A' button is pressed
- new JoystickButton(m_driverController, Button.kA.value).whenPressed(m_instantCommand1);
+ new JoystickButton(m_driverController, Button.kA.value).onTrue(m_instantCommand1);
// Run instant command 2 when the 'X' button is pressed
- new JoystickButton(m_driverController, Button.kX.value).whenPressed(m_instantCommand2);
+ new JoystickButton(m_driverController, Button.kX.value).onTrue(m_instantCommand2);
// Run instant command 3 when the 'Y' button is held; release early to interrupt
- new JoystickButton(m_driverController, Button.kY.value).whenHeld(m_waitCommand);
+ new JoystickButton(m_driverController, Button.kY.value).whileTrue(m_waitCommand);
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java
index 03ee906979..33adbf9a99 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java
@@ -18,6 +18,7 @@ import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RamseteCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
@@ -66,8 +67,8 @@ public class RobotContainer {
private void configureButtonBindings() {
// Drive at half speed when the right bumper is held
new JoystickButton(m_driverController, Button.kRightBumper.value)
- .whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
- .whenReleased(() -> m_robotDrive.setMaxOutput(1));
+ .onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
+ .onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
}
public DriveSubsystem getRobotDrive() {