001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.wpilibj.event;
006
007import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
008
009import edu.wpi.first.math.filter.Debouncer;
010import java.util.function.BiFunction;
011import java.util.function.BooleanSupplier;
012
013/**
014 * This class provides an easy way to link actions to high-active logic signals. Each object
015 * represents a digital signal to which callback actions can be bound using {@link
016 * #ifHigh(Runnable)}.
017 *
018 * <p>These signals can easily be composed for advanced functionality using {@link
019 * #and(BooleanSupplier)}, {@link #or(BooleanSupplier)}, {@link #negate()} etc.
020 *
021 * <p>To get an event that activates only when this one changes, see {@link #falling()} and {@link
022 * #rising()}.
023 */
024public class BooleanEvent implements BooleanSupplier {
025  /** Poller loop. */
026  protected final EventLoop m_loop;
027  /** Condition. */
028  private final BooleanSupplier m_signal;
029
030  /**
031   * Creates a new event with the given signal determining whether it is active.
032   *
033   * @param loop the loop that polls this event
034   * @param signal the digital signal represented by this object.
035   */
036  public BooleanEvent(EventLoop loop, BooleanSupplier signal) {
037    m_loop = requireNonNullParam(loop, "loop", "BooleanEvent");
038    m_signal = requireNonNullParam(signal, "signal", "BooleanEvent");
039  }
040
041  /**
042   * Check the state of this signal (high or low).
043   *
044   * @return true for the high state, false for the low state.
045   */
046  @Override
047  public final boolean getAsBoolean() {
048    return m_signal.getAsBoolean();
049  }
050
051  /**
052   * Bind an action to this event.
053   *
054   * @param action the action to run if this event is active.
055   */
056  public final void ifHigh(Runnable action) {
057    m_loop.bind(
058        () -> {
059          if (m_signal.getAsBoolean()) {
060            action.run();
061          }
062        });
063  }
064
065  /**
066   * Get a new event that events only when this one newly changes to true.
067   *
068   * @return a new event representing when this one newly changes to true.
069   */
070  public BooleanEvent rising() {
071    return new BooleanEvent(
072        m_loop,
073        new BooleanSupplier() {
074          private boolean m_previous = m_signal.getAsBoolean();
075
076          @Override
077          public boolean getAsBoolean() {
078            boolean present = m_signal.getAsBoolean();
079            boolean ret = !m_previous && present;
080            m_previous = present;
081            return ret;
082          }
083        });
084  }
085
086  /**
087   * Get a new event that triggers only when this one newly changes to false.
088   *
089   * @return a new event representing when this one newly changes to false.
090   */
091  public BooleanEvent falling() {
092    return new BooleanEvent(
093        m_loop,
094        new BooleanSupplier() {
095          private boolean m_previous = m_signal.getAsBoolean();
096
097          @Override
098          public boolean getAsBoolean() {
099            boolean present = m_signal.getAsBoolean();
100            boolean ret = m_previous && !present;
101            m_previous = present;
102            return ret;
103          }
104        });
105  }
106
107  /**
108   * Creates a new debounced event from this event - it will become active when this event has been
109   * active for longer than the specified period.
110   *
111   * @param seconds The debounce period.
112   * @return The debounced event (rising edges debounced only)
113   */
114  public BooleanEvent debounce(double seconds) {
115    return debounce(seconds, Debouncer.DebounceType.kRising);
116  }
117
118  /**
119   * Creates a new debounced event from this event - it will become active when this event has been
120   * active for longer than the specified period.
121   *
122   * @param seconds The debounce period.
123   * @param type The debounce type.
124   * @return The debounced event.
125   */
126  public BooleanEvent debounce(double seconds, Debouncer.DebounceType type) {
127    return new BooleanEvent(
128        m_loop,
129        new BooleanSupplier() {
130          private final Debouncer m_debouncer = new Debouncer(seconds, type);
131
132          @Override
133          public boolean getAsBoolean() {
134            return m_debouncer.calculate(m_signal.getAsBoolean());
135          }
136        });
137  }
138
139  /**
140   * Creates a new event that is active when this event is inactive, i.e. that acts as the negation
141   * of this event.
142   *
143   * @return the negated event
144   */
145  public BooleanEvent negate() {
146    return new BooleanEvent(m_loop, () -> !m_signal.getAsBoolean());
147  }
148
149  /**
150   * Composes this event with another event, returning a new signal that is in the high state when
151   * both signals are in the high state.
152   *
153   * <p>The new event will use this event's polling loop.
154   *
155   * @param other the event to compose with
156   * @return the event that is active when both events are active
157   */
158  public BooleanEvent and(BooleanSupplier other) {
159    requireNonNullParam(other, "other", "and");
160    return new BooleanEvent(m_loop, () -> m_signal.getAsBoolean() && other.getAsBoolean());
161  }
162
163  /**
164   * Composes this event with another event, returning a new signal that is high when either signal
165   * is high.
166   *
167   * <p>The new event will use this event's polling loop.
168   *
169   * @param other the event to compose with
170   * @return a signal that is high when either signal is high.
171   */
172  public BooleanEvent or(BooleanSupplier other) {
173    requireNonNullParam(other, "other", "or");
174    return new BooleanEvent(m_loop, () -> m_signal.getAsBoolean() || other.getAsBoolean());
175  }
176
177  /**
178   * A method to "downcast" a BooleanEvent instance to a subclass (for example, to a command-based
179   * version of this class).
180   *
181   * @param ctor a method reference to the constructor of the subclass that accepts the loop as the
182   *     first parameter and the condition/signal as the second.
183   * @param <T> the subclass type
184   * @return an instance of the subclass.
185   */
186  public <T extends BooleanSupplier> T castTo(BiFunction<EventLoop, BooleanSupplier, T> ctor) {
187    return ctor.apply(m_loop, m_signal);
188  }
189}