Class Trigger
java.lang.Object
edu.wpi.first.wpilibj2.command.button.Trigger
- Direct Known Subclasses:
- Button
public class Trigger
extends java.lang.Object
This class provides an easy way to link commands to inputs.
 
It is very easy to link a button to a command. For instance, you could link the trigger button of a joystick to a "score" command.
It is encouraged that teams write a subclass of Trigger if they want to have something
 unusual (for instance, if they want to react to the user holding a button while the robot is
 reading a certain sensor input). For this, they only have to write the get()
 method to get the full functionality of the Trigger class.
- 
Constructor Summary
- 
Method SummaryModifier and Type Method Description Triggerand(Trigger trigger)Composes this trigger with another trigger, returning a new trigger that is active when both triggers are active.TriggercancelWhenActive(Command command)Cancels a command when the trigger becomes active.booleanget()Returns whether or not the trigger is active.Triggernegate()Creates a new trigger that is active when this trigger is inactive, i.e.Triggeror(Trigger trigger)Composes this trigger with another trigger, returning a new trigger that is active when either trigger is active.TriggertoggleWhenActive(Command command)Toggles a command when the trigger becomes active.TriggertoggleWhenActive(Command command, boolean interruptible)Toggles a command when the trigger becomes active.TriggerwhenActive(Command command)Starts the given command whenever the trigger just becomes active.TriggerwhenActive(Command command, boolean interruptible)Starts the given command whenever the trigger just becomes active.TriggerwhenActive(java.lang.Runnable toRun)Runs the given runnable whenever the trigger just becomes active.TriggerwhenInactive(Command command)Starts the command when the trigger becomes inactive.TriggerwhenInactive(Command command, boolean interruptible)Starts the command when the trigger becomes inactive.TriggerwhenInactive(java.lang.Runnable toRun)Runs the given runnable when the trigger becomes inactive.TriggerwhileActiveContinuous(Command command)Constantly starts the given command while the button is held.TriggerwhileActiveContinuous(Command command, boolean interruptible)Constantly starts the given command while the button is held.TriggerwhileActiveContinuous(java.lang.Runnable toRun)Constantly runs the given runnable while the button is held.TriggerwhileActiveOnce(Command command)Starts the given command when the trigger initially becomes active, and ends it when it becomes inactive, but does not re-start it in-between.TriggerwhileActiveOnce(Command command, boolean interruptible)Starts the given command when the trigger initially becomes active, and ends it when it becomes inactive, but does not re-start it in-between.
- 
Constructor Details- 
Triggerpublic Trigger(java.util.function.BooleanSupplier isActive)Creates a new trigger with the given condition determining whether it is active.- Parameters:
- isActive- returns whether or not the trigger should be active
 
- 
Triggerpublic Trigger()Creates a new trigger that is always inactive. Useful only as a no-arg constructor for subclasses that will be overridingget()anyway.
 
- 
- 
Method Details- 
getpublic boolean get()Returns whether or not the trigger is active.This method will be called repeatedly a command is linked to the Trigger. - Returns:
- whether or not the trigger condition is active.
 
- 
whenActiveStarts the given command whenever the trigger just becomes active.- Parameters:
- command- the command to start
- interruptible- whether the command is interruptible
- Returns:
- this trigger, so calls can be chained
 
- 
whenActiveStarts the given command whenever the trigger just becomes active. The command is set to be interruptible.- Parameters:
- command- the command to start
- Returns:
- this trigger, so calls can be chained
 
- 
whenActiveRuns the given runnable whenever the trigger just becomes active.- Parameters:
- toRun- the runnable to run
- Returns:
- this trigger, so calls can be chained
 
- 
whileActiveContinuousConstantly starts the given command while the button is held.Command.schedule(boolean)will be called repeatedly while the trigger is active, and will be canceled when the trigger becomes inactive.- Parameters:
- command- the command to start
- interruptible- whether the command is interruptible
- Returns:
- this trigger, so calls can be chained
 
- 
whileActiveContinuousConstantly starts the given command while the button is held.Command.schedule(boolean)will be called repeatedly while the trigger is active, and will be canceled when the trigger becomes inactive. The command is set to be interruptible.- Parameters:
- command- the command to start
- Returns:
- this trigger, so calls can be chained
 
- 
whileActiveContinuousConstantly runs the given runnable while the button is held.- Parameters:
- toRun- the runnable to run
- Returns:
- this trigger, so calls can be chained
 
- 
whileActiveOnceStarts the given command when the trigger initially becomes active, and ends it when it becomes inactive, but does not re-start it in-between.- Parameters:
- command- the command to start
- interruptible- whether the command is interruptible
- Returns:
- this trigger, so calls can be chained
 
- 
whileActiveOnceStarts the given command when the trigger initially becomes active, and ends it when it becomes inactive, but does not re-start it in-between. The command is set to be interruptible.- Parameters:
- command- the command to start
- Returns:
- this trigger, so calls can be chained
 
- 
whenInactiveStarts the command when the trigger becomes inactive.- Parameters:
- command- the command to start
- interruptible- whether the command is interruptible
- Returns:
- this trigger, so calls can be chained
 
- 
whenInactiveStarts the command when the trigger becomes inactive. The command is set to be interruptible.- Parameters:
- command- the command to start
- Returns:
- this trigger, so calls can be chained
 
- 
whenInactiveRuns the given runnable when the trigger becomes inactive.- Parameters:
- toRun- the runnable to run
- Returns:
- this trigger, so calls can be chained
 
- 
toggleWhenActiveToggles a command when the trigger becomes active.- Parameters:
- command- the command to toggle
- interruptible- whether the command is interruptible
- Returns:
- this trigger, so calls can be chained
 
- 
toggleWhenActiveToggles a command when the trigger becomes active. The command is set to be interruptible.- Parameters:
- command- the command to toggle
- Returns:
- this trigger, so calls can be chained
 
- 
cancelWhenActiveCancels a command when the trigger becomes active.- Parameters:
- command- the command to cancel
- Returns:
- this trigger, so calls can be chained
 
- 
andComposes this trigger with another trigger, returning a new trigger that is active when both triggers are active.- Parameters:
- trigger- the trigger to compose with
- Returns:
- the trigger that is active when both triggers are active
 
- 
orComposes this trigger with another trigger, returning a new trigger that is active when either trigger is active.- Parameters:
- trigger- the trigger to compose with
- Returns:
- the trigger that is active when either trigger is active
 
- 
negateCreates a new trigger that is active when this trigger is inactive, i.e. that acts as the negation of this trigger.- Returns:
- the negated trigger
 
 
-