Class Trigger

java.lang.Object
edu.wpi.first.wpilibj2.command.button.Trigger
All Implemented Interfaces:
BooleanSupplier
Direct Known Subclasses:
InternalButton, JoystickButton, NetworkButton, POVButton

public class Trigger extends Object implements BooleanSupplier
This class provides an easy way to link commands to conditions.

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.

Triggers can easily be composed for advanced functionality using the and(BooleanSupplier), or(BooleanSupplier), negate() operators.

This class is provided by the NewCommands VendorDep

  • Constructor Summary

    Constructors
    Constructor
    Description
    Trigger(EventLoop loop, BooleanSupplier condition)
    Creates a new trigger based on the given condition.
    Creates a new trigger based on the given condition.
  • Method Summary

    Modifier and Type
    Method
    Description
    Composes two triggers with logical AND.
    debounce(double seconds)
    Creates a new debounced trigger from this trigger - it will become active when this trigger has been active for longer than the specified period.
    debounce(double seconds, Debouncer.DebounceType type)
    Creates a new debounced trigger from this trigger - it will become active when this trigger has been active for longer than the specified period.
    boolean
     
    multiPress(int requiredPresses, double windowTime)
    Creates a new multi-press trigger from this trigger - it will become active when this trigger has been activated the required number of times within the specified time window.
    Creates a new trigger that is active when this trigger is inactive, i.e.
    onChange(Command command)
    Starts the command when the condition changes.
    onFalse(Command command)
    Starts the given command whenever the condition changes from `true` to `false`.
    onTrue(Command command)
    Starts the given command whenever the condition changes from `false` to `true`.
    Composes two triggers with logical OR.
    Toggles a command when the condition changes from `true` to `false`.
    Toggles a command when the condition changes from `false` to `true`.
    Starts the given command when the condition changes to `false` and cancels it when the condition changes to `true`.
    whileTrue(Command command)
    Starts the given command when the condition changes to `true` and cancels it when the condition changes to `false`.

    Methods inherited from class java.lang.Object

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

    • Trigger

      public Trigger(EventLoop loop, BooleanSupplier condition)
      Creates a new trigger based on the given condition.
      Parameters:
      loop - The loop instance that polls this trigger.
      condition - the condition represented by this trigger
    • Trigger

      public Trigger(BooleanSupplier condition)
      Creates a new trigger based on the given condition.

      Polled by the default scheduler button loop.

      Parameters:
      condition - the condition represented by this trigger
  • Method Details

    • onChange

      public Trigger onChange(Command command)
      Starts the command when the condition changes.
      Parameters:
      command - the command to start
      Returns:
      this trigger, so calls can be chained
    • onTrue

      public Trigger onTrue(Command command)
      Starts the given command whenever the condition changes from `false` to `true`.
      Parameters:
      command - the command to start
      Returns:
      this trigger, so calls can be chained
    • onFalse

      public Trigger onFalse(Command command)
      Starts the given command whenever the condition changes from `true` to `false`.
      Parameters:
      command - the command to start
      Returns:
      this trigger, so calls can be chained
    • whileTrue

      public Trigger whileTrue(Command command)
      Starts the given command when the condition changes to `true` and cancels it when the condition changes to `false`.

      Doesn't re-start the command if it ends while the condition is still `true`. If the command should restart, see RepeatCommand.

      Parameters:
      command - the command to start
      Returns:
      this trigger, so calls can be chained
    • whileFalse

      public Trigger whileFalse(Command command)
      Starts the given command when the condition changes to `false` and cancels it when the condition changes to `true`.

      Doesn't re-start the command if it ends while the condition is still `false`. If the command should restart, see RepeatCommand.

      Parameters:
      command - the command to start
      Returns:
      this trigger, so calls can be chained
    • toggleOnTrue

      public Trigger toggleOnTrue(Command command)
      Toggles a command when the condition changes from `false` to `true`.
      Parameters:
      command - the command to toggle
      Returns:
      this trigger, so calls can be chained
    • toggleOnFalse

      public Trigger toggleOnFalse(Command command)
      Toggles a command when the condition changes from `true` to `false`.
      Parameters:
      command - the command to toggle
      Returns:
      this trigger, so calls can be chained
    • getAsBoolean

      public boolean getAsBoolean()
      Specified by:
      getAsBoolean in interface BooleanSupplier
    • and

      public Trigger and(BooleanSupplier trigger)
      Composes two triggers with logical AND.
      Parameters:
      trigger - the condition to compose with
      Returns:
      A trigger which is active when both component triggers are active.
    • or

      public Trigger or(BooleanSupplier trigger)
      Composes two triggers with logical OR.
      Parameters:
      trigger - the condition to compose with
      Returns:
      A trigger which is active when either component 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
    • debounce

      public Trigger debounce(double seconds)
      Creates a new debounced trigger from this trigger - it will become active when this trigger has been active for longer than the specified period.
      Parameters:
      seconds - The debounce period.
      Returns:
      The debounced trigger (rising edges debounced only)
    • debounce

      public Trigger debounce(double seconds, Debouncer.DebounceType type)
      Creates a new debounced trigger from this trigger - it will become active when this trigger has been active for longer than the specified period.
      Parameters:
      seconds - The debounce period.
      type - The debounce type.
      Returns:
      The debounced trigger.
    • multiPress

      public Trigger multiPress(int requiredPresses, double windowTime)
      Creates a new multi-press trigger from this trigger - it will become active when this trigger has been activated the required number of times within the specified time window.

      This is useful for implementing "double-click" style functionality.

      Input for this must be stable, consider using a Debouncer before this to avoid counting noise as multiple presses.

      Parameters:
      requiredPresses - The number of presses required.
      windowTime - The number of seconds in which the presses must occur.
      Returns:
      The multi-press trigger.