Class Trigger

java.lang.Object
org.wpilib.commands3.Trigger
All Implemented Interfaces:
BooleanSupplier
Direct Known Subclasses:
InternalButton, JoystickButton, NetworkButton, POVButton

public class Trigger extends Object implements BooleanSupplier
Triggers allow users to specify conditions for when commands should run. Triggers can be set up to read from joystick and controller buttons (eg CommandXboxController.x()) or be customized to read sensor values or any other arbitrary true/false condition.

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.

Trigger bindings created inside a running command will only be active while that command is running. This is useful for defining trigger-based behavior only in a certain scope and avoids needing to create dozens of global triggers. Any commands scheduled by these triggers will be canceled when the enclosing command exits.


 Command shootWhileAiming = Command.noRequirements().executing(co -> {
   turret.atTarget.onTrue(shooter.shootOnce());
   co.await(turret.lockOnGoal());
 }).named("Shoot While Aiming");
 controller.rightBumper().whileTrue(shootWhileAiming);
 
  • Constructor Details

    • Trigger

      public Trigger(Scheduler scheduler, BooleanSupplier condition)
      Creates a new trigger based on the given condition. Polled by the scheduler's default event loop.
      Parameters:
      scheduler - The scheduler that should execute triggered commands.
      condition - the condition represented by this trigger
    • Trigger

      public Trigger(BooleanSupplier condition)
      Creates a new trigger based on the given condition. Triggered commands are executed by the default scheduler.

      Polled by the default scheduler button loop.

      Parameters:
      condition - the condition represented by this trigger
    • Trigger

      public Trigger(Scheduler scheduler, EventLoop loop, BooleanSupplier condition)
      Creates a new trigger based on the given condition.
      Parameters:
      scheduler - The scheduler that should execute triggered commands.
      loop - The event loop to poll the trigger.
      condition - the condition represented by this trigger
  • Method Details

    • 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`.

      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`.

      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(Time duration)
      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:
      duration - The debounce period.
      Returns:
      The debounced trigger (rising edges debounced only)
    • debounce

      public Trigger debounce(Time duration, 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:
      duration - The debounce period.
      type - The debounce type.
      Returns:
      The debounced trigger.