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

    Constructors 
    Constructor Description
    Trigger()
    Creates a new trigger that is always inactive.
    Trigger​(java.util.function.BooleanSupplier isActive)
    Creates a new trigger with the given condition determining whether it is active.
  • Method Summary

    Modifier and Type Method Description
    Trigger and​(Trigger trigger)
    Composes this trigger with another trigger, returning a new trigger that is active when both triggers are active.
    Trigger cancelWhenActive​(Command command)
    Cancels a command when the trigger becomes active.
    boolean get()
    Returns whether or not the trigger is active.
    Trigger negate()
    Creates a new trigger that is active when this trigger is inactive, i.e.
    Trigger or​(Trigger trigger)
    Composes this trigger with another trigger, returning a new trigger that is active when either trigger is active.
    Trigger toggleWhenActive​(Command command)
    Toggles a command when the trigger becomes active.
    Trigger toggleWhenActive​(Command command, boolean interruptible)
    Toggles a command when the trigger becomes active.
    Trigger whenActive​(Command command)
    Starts the given command whenever the trigger just becomes active.
    Trigger whenActive​(Command command, boolean interruptible)
    Starts the given command whenever the trigger just becomes active.
    Trigger whenActive​(java.lang.Runnable toRun)
    Runs the given runnable whenever the trigger just becomes active.
    Trigger whenInactive​(Command command)
    Starts the command when the trigger becomes inactive.
    Trigger whenInactive​(Command command, boolean interruptible)
    Starts the command when the trigger becomes inactive.
    Trigger whenInactive​(java.lang.Runnable toRun)
    Runs the given runnable when the trigger becomes inactive.
    Trigger whileActiveContinuous​(Command command)
    Constantly starts the given command while the button is held.
    Trigger whileActiveContinuous​(Command command, boolean interruptible)
    Constantly starts the given command while the button is held.
    Trigger whileActiveContinuous​(java.lang.Runnable toRun)
    Constantly runs the given runnable while the button is held.
    Trigger whileActiveOnce​(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.
    Trigger whileActiveOnce​(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.

    Methods inherited from class java.lang.Object

    equals, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Constructor Details

    • Trigger

      public 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
    • Trigger

      public Trigger()
      Creates a new trigger that is always inactive. Useful only as a no-arg constructor for subclasses that will be overriding get() anyway.
  • Method Details

    • get

      public 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.
    • whenActive

      public Trigger whenActive​(Command command, boolean interruptible)
      Starts 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
    • whenActive

      public Trigger whenActive​(Command command)
      Starts 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
    • whenActive

      public Trigger whenActive​(java.lang.Runnable toRun)
      Runs the given runnable whenever the trigger just becomes active.
      Parameters:
      toRun - the runnable to run
      Returns:
      this trigger, so calls can be chained
    • whileActiveContinuous

      public Trigger whileActiveContinuous​(Command command, boolean interruptible)
      Constantly 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
    • whileActiveContinuous

      public Trigger whileActiveContinuous​(Command command)
      Constantly 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
    • whileActiveContinuous

      public Trigger whileActiveContinuous​(java.lang.Runnable toRun)
      Constantly runs the given runnable while the button is held.
      Parameters:
      toRun - the runnable to run
      Returns:
      this trigger, so calls can be chained
    • whileActiveOnce

      public Trigger whileActiveOnce​(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.
      Parameters:
      command - the command to start
      interruptible - whether the command is interruptible
      Returns:
      this trigger, so calls can be chained
    • whileActiveOnce

      public Trigger whileActiveOnce​(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. The command is set to be interruptible.
      Parameters:
      command - the command to start
      Returns:
      this trigger, so calls can be chained
    • whenInactive

      public Trigger whenInactive​(Command command, boolean interruptible)
      Starts 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
    • whenInactive

      public Trigger whenInactive​(Command command)
      Starts 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
    • whenInactive

      public Trigger whenInactive​(java.lang.Runnable toRun)
      Runs the given runnable when the trigger becomes inactive.
      Parameters:
      toRun - the runnable to run
      Returns:
      this trigger, so calls can be chained
    • toggleWhenActive

      public Trigger toggleWhenActive​(Command command, boolean interruptible)
      Toggles 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
    • toggleWhenActive

      public Trigger toggleWhenActive​(Command command)
      Toggles 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
    • cancelWhenActive

      public Trigger cancelWhenActive​(Command command)
      Cancels a command when the trigger becomes active.
      Parameters:
      command - the command to cancel
      Returns:
      this trigger, so calls can be chained
    • and

      public Trigger and​(Trigger trigger)
      Composes 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
    • or

      public Trigger or​(Trigger trigger)
      Composes 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
    • negate

      public Trigger negate()
      Creates 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