Class BooleanEvent

java.lang.Object
edu.wpi.first.wpilibj.event.BooleanEvent
All Implemented Interfaces:
BooleanSupplier
Direct Known Subclasses:
NetworkBooleanEvent

public class BooleanEvent
extends Object
implements BooleanSupplier
This class provides an easy way to link actions to high-active logic signals. Each object represents a digital signal to which callback actions can be bound using ifHigh(Runnable).

These signals can easily be composed for advanced functionality using and(BooleanSupplier), or(BooleanSupplier), negate() etc.

To get an event that activates only when this one changes, see falling() and rising().

  • Field Details

  • Constructor Details

    • BooleanEvent

      public BooleanEvent​(EventLoop loop, BooleanSupplier signal)
      Creates a new event with the given signal determining whether it is active.
      Parameters:
      loop - the loop that polls this event
      signal - the digital signal represented by this object.
  • Method Details

    • getAsBoolean

      public final boolean getAsBoolean()
      Check the state of this signal (high or low) as of the last loop poll.
      Specified by:
      getAsBoolean in interface BooleanSupplier
      Returns:
      true for the high state, false for the low state. If the event was never polled, it returns the state at event construction.
    • ifHigh

      public final void ifHigh​(Runnable action)
      Bind an action to this event.
      Parameters:
      action - the action to run if this event is active.
    • rising

      public BooleanEvent rising()
      Get a new event that events only when this one newly changes to true.
      Returns:
      a new event representing when this one newly changes to true.
    • falling

      Get a new event that triggers only when this one newly changes to false.
      Returns:
      a new event representing when this one newly changes to false.
    • debounce

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

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

      public BooleanEvent negate()
      Creates a new event that is active when this event is inactive, i.e. that acts as the negation of this event.
      Returns:
      the negated event
    • and

      public BooleanEvent and​(BooleanSupplier other)
      Composes this event with another event, returning a new signal that is in the high state when both signals are in the high state.

      The events must use the same event loop. If the events use different event loops, the composed signal won't update until both loops are polled.

      Parameters:
      other - the event to compose with
      Returns:
      the event that is active when both events are active
    • or

      public BooleanEvent or​(BooleanSupplier other)
      Composes this event with another event, returning a new signal that is high when either signal is high.

      The events must use the same event loop. If the events use different event loops, the composed signal won't update until both loops are polled.

      Parameters:
      other - the event to compose with
      Returns:
      a signal that is high when either signal is high.
    • castTo

      public <T extends BooleanSupplier> T castTo​(BiFunction<EventLoop,​BooleanSupplier,​T> ctor)
      A method to "downcast" a BooleanEvent instance to a subclass (for example, to a command-based version of this class).
      Type Parameters:
      T - the subclass type
      Parameters:
      ctor - a method reference to the constructor of the subclass that accepts the loop as the first parameter and the condition/signal as the second.
      Returns:
      an instance of the subclass.