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.wpilibj2.command.button;
006
007import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
008
009import edu.wpi.first.math.filter.Debouncer;
010import edu.wpi.first.wpilibj.event.EventLoop;
011import edu.wpi.first.wpilibj2.command.Command;
012import edu.wpi.first.wpilibj2.command.CommandScheduler;
013import java.util.function.BooleanSupplier;
014
015/**
016 * This class provides an easy way to link commands to conditions.
017 *
018 * <p>It is very easy to link a button to a command. For instance, you could link the trigger button
019 * of a joystick to a "score" command.
020 *
021 * <p>Triggers can easily be composed for advanced functionality using the {@link
022 * #and(BooleanSupplier)}, {@link #or(BooleanSupplier)}, {@link #negate()} operators.
023 *
024 * <p>This class is provided by the NewCommands VendorDep
025 */
026public class Trigger implements BooleanSupplier {
027  private final BooleanSupplier m_condition;
028  private final EventLoop m_loop;
029
030  /**
031   * Creates a new trigger based on the given condition.
032   *
033   * @param loop The loop instance that polls this trigger.
034   * @param condition the condition represented by this trigger
035   */
036  public Trigger(EventLoop loop, BooleanSupplier condition) {
037    m_loop = requireNonNullParam(loop, "loop", "Trigger");
038    m_condition = requireNonNullParam(condition, "condition", "Trigger");
039  }
040
041  /**
042   * Creates a new trigger based on the given condition.
043   *
044   * <p>Polled by the default scheduler button loop.
045   *
046   * @param condition the condition represented by this trigger
047   */
048  public Trigger(BooleanSupplier condition) {
049    this(CommandScheduler.getInstance().getDefaultButtonLoop(), condition);
050  }
051
052  /**
053   * Starts the command when the condition changes.
054   *
055   * @param command the command to start
056   * @return this trigger, so calls can be chained
057   */
058  public Trigger onChange(Command command) {
059    requireNonNullParam(command, "command", "onChange");
060    m_loop.bind(
061        new Runnable() {
062          private boolean m_pressedLast = m_condition.getAsBoolean();
063
064          @Override
065          public void run() {
066            boolean pressed = m_condition.getAsBoolean();
067
068            if (m_pressedLast != pressed) {
069              command.schedule();
070            }
071
072            m_pressedLast = pressed;
073          }
074        });
075    return this;
076  }
077
078  /**
079   * Starts the given command whenever the condition changes from `false` to `true`.
080   *
081   * @param command the command to start
082   * @return this trigger, so calls can be chained
083   */
084  public Trigger onTrue(Command command) {
085    requireNonNullParam(command, "command", "onTrue");
086    m_loop.bind(
087        new Runnable() {
088          private boolean m_pressedLast = m_condition.getAsBoolean();
089
090          @Override
091          public void run() {
092            boolean pressed = m_condition.getAsBoolean();
093
094            if (!m_pressedLast && pressed) {
095              command.schedule();
096            }
097
098            m_pressedLast = pressed;
099          }
100        });
101    return this;
102  }
103
104  /**
105   * Starts the given command whenever the condition changes from `true` to `false`.
106   *
107   * @param command the command to start
108   * @return this trigger, so calls can be chained
109   */
110  public Trigger onFalse(Command command) {
111    requireNonNullParam(command, "command", "onFalse");
112    m_loop.bind(
113        new Runnable() {
114          private boolean m_pressedLast = m_condition.getAsBoolean();
115
116          @Override
117          public void run() {
118            boolean pressed = m_condition.getAsBoolean();
119
120            if (m_pressedLast && !pressed) {
121              command.schedule();
122            }
123
124            m_pressedLast = pressed;
125          }
126        });
127    return this;
128  }
129
130  /**
131   * Starts the given command when the condition changes to `true` and cancels it when the condition
132   * changes to `false`.
133   *
134   * <p>Doesn't re-start the command if it ends while the condition is still `true`. If the command
135   * should restart, see {@link edu.wpi.first.wpilibj2.command.RepeatCommand}.
136   *
137   * @param command the command to start
138   * @return this trigger, so calls can be chained
139   */
140  public Trigger whileTrue(Command command) {
141    requireNonNullParam(command, "command", "whileTrue");
142    m_loop.bind(
143        new Runnable() {
144          private boolean m_pressedLast = m_condition.getAsBoolean();
145
146          @Override
147          public void run() {
148            boolean pressed = m_condition.getAsBoolean();
149
150            if (!m_pressedLast && pressed) {
151              command.schedule();
152            } else if (m_pressedLast && !pressed) {
153              command.cancel();
154            }
155
156            m_pressedLast = pressed;
157          }
158        });
159    return this;
160  }
161
162  /**
163   * Starts the given command when the condition changes to `false` and cancels it when the
164   * condition changes to `true`.
165   *
166   * <p>Doesn't re-start the command if it ends while the condition is still `false`. If the command
167   * should restart, see {@link edu.wpi.first.wpilibj2.command.RepeatCommand}.
168   *
169   * @param command the command to start
170   * @return this trigger, so calls can be chained
171   */
172  public Trigger whileFalse(Command command) {
173    requireNonNullParam(command, "command", "whileFalse");
174    m_loop.bind(
175        new Runnable() {
176          private boolean m_pressedLast = m_condition.getAsBoolean();
177
178          @Override
179          public void run() {
180            boolean pressed = m_condition.getAsBoolean();
181
182            if (m_pressedLast && !pressed) {
183              command.schedule();
184            } else if (!m_pressedLast && pressed) {
185              command.cancel();
186            }
187
188            m_pressedLast = pressed;
189          }
190        });
191    return this;
192  }
193
194  /**
195   * Toggles a command when the condition changes from `false` to `true`.
196   *
197   * @param command the command to toggle
198   * @return this trigger, so calls can be chained
199   */
200  public Trigger toggleOnTrue(Command command) {
201    requireNonNullParam(command, "command", "toggleOnTrue");
202    m_loop.bind(
203        new Runnable() {
204          private boolean m_pressedLast = m_condition.getAsBoolean();
205
206          @Override
207          public void run() {
208            boolean pressed = m_condition.getAsBoolean();
209
210            if (!m_pressedLast && pressed) {
211              if (command.isScheduled()) {
212                command.cancel();
213              } else {
214                command.schedule();
215              }
216            }
217
218            m_pressedLast = pressed;
219          }
220        });
221    return this;
222  }
223
224  /**
225   * Toggles a command when the condition changes from `true` to `false`.
226   *
227   * @param command the command to toggle
228   * @return this trigger, so calls can be chained
229   */
230  public Trigger toggleOnFalse(Command command) {
231    requireNonNullParam(command, "command", "toggleOnFalse");
232    m_loop.bind(
233        new Runnable() {
234          private boolean m_pressedLast = m_condition.getAsBoolean();
235
236          @Override
237          public void run() {
238            boolean pressed = m_condition.getAsBoolean();
239
240            if (m_pressedLast && !pressed) {
241              if (command.isScheduled()) {
242                command.cancel();
243              } else {
244                command.schedule();
245              }
246            }
247
248            m_pressedLast = pressed;
249          }
250        });
251    return this;
252  }
253
254  @Override
255  public boolean getAsBoolean() {
256    return m_condition.getAsBoolean();
257  }
258
259  /**
260   * Composes two triggers with logical AND.
261   *
262   * @param trigger the condition to compose with
263   * @return A trigger which is active when both component triggers are active.
264   */
265  public Trigger and(BooleanSupplier trigger) {
266    return new Trigger(m_loop, () -> m_condition.getAsBoolean() && trigger.getAsBoolean());
267  }
268
269  /**
270   * Composes two triggers with logical OR.
271   *
272   * @param trigger the condition to compose with
273   * @return A trigger which is active when either component trigger is active.
274   */
275  public Trigger or(BooleanSupplier trigger) {
276    return new Trigger(m_loop, () -> m_condition.getAsBoolean() || trigger.getAsBoolean());
277  }
278
279  /**
280   * Creates a new trigger that is active when this trigger is inactive, i.e. that acts as the
281   * negation of this trigger.
282   *
283   * @return the negated trigger
284   */
285  public Trigger negate() {
286    return new Trigger(m_loop, () -> !m_condition.getAsBoolean());
287  }
288
289  /**
290   * Creates a new debounced trigger from this trigger - it will become active when this trigger has
291   * been active for longer than the specified period.
292   *
293   * @param seconds The debounce period.
294   * @return The debounced trigger (rising edges debounced only)
295   */
296  public Trigger debounce(double seconds) {
297    return debounce(seconds, Debouncer.DebounceType.kRising);
298  }
299
300  /**
301   * Creates a new debounced trigger from this trigger - it will become active when this trigger has
302   * been active for longer than the specified period.
303   *
304   * @param seconds The debounce period.
305   * @param type The debounce type.
306   * @return The debounced trigger.
307   */
308  public Trigger debounce(double seconds, Debouncer.DebounceType type) {
309    return new Trigger(
310        m_loop,
311        new BooleanSupplier() {
312          final Debouncer m_debouncer = new Debouncer(seconds, type);
313
314          @Override
315          public boolean getAsBoolean() {
316            return m_debouncer.calculate(m_condition.getAsBoolean());
317          }
318        });
319  }
320}