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