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