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.BooleanEvent;
011import edu.wpi.first.wpilibj.event.EventLoop;
012import edu.wpi.first.wpilibj2.command.Command;
013import edu.wpi.first.wpilibj2.command.CommandScheduler;
014import edu.wpi.first.wpilibj2.command.InstantCommand;
015import edu.wpi.first.wpilibj2.command.Subsystem;
016import java.util.function.BooleanSupplier;
017
018/**
019 * This class provides an easy way to link commands to conditions.
020 *
021 * <p>It is very easy to link a button to a command. For instance, you could link the trigger button
022 * of a joystick to a "score" command.
023 *
024 * <p>Triggers can easily be composed for advanced functionality using the {@link
025 * #and(BooleanSupplier)}, {@link #or(BooleanSupplier)}, {@link #negate()} operators.
026 *
027 * <p>This class is provided by the NewCommands VendorDep
028 */
029public class Trigger implements BooleanSupplier {
030  private final BooleanSupplier m_condition;
031  private final EventLoop m_loop;
032
033  /**
034   * Creates a new trigger based on the given condition.
035   *
036   * @param loop The loop instance that polls this trigger.
037   * @param condition the condition represented by this trigger
038   */
039  public Trigger(EventLoop loop, BooleanSupplier condition) {
040    m_loop = requireNonNullParam(loop, "loop", "Trigger");
041    m_condition = requireNonNullParam(condition, "condition", "Trigger");
042  }
043
044  /**
045   * Creates a new trigger based on the given condition.
046   *
047   * <p>Polled by the default scheduler button loop.
048   *
049   * @param condition the condition represented by this trigger
050   */
051  public Trigger(BooleanSupplier condition) {
052    this(CommandScheduler.getInstance().getDefaultButtonLoop(), condition);
053  }
054
055  /** Creates a new trigger that is always `false`. */
056  @Deprecated
057  public Trigger() {
058    this(() -> false);
059  }
060
061  /**
062   * Starts the given command whenever the condition changes from `false` to `true`.
063   *
064   * @param command the command to start
065   * @return this trigger, so calls can be chained
066   */
067  public Trigger onTrue(Command command) {
068    requireNonNullParam(command, "command", "onRising");
069    m_loop.bind(
070        new Runnable() {
071          private boolean m_pressedLast = m_condition.getAsBoolean();
072
073          @Override
074          public void run() {
075            boolean pressed = m_condition.getAsBoolean();
076
077            if (!m_pressedLast && pressed) {
078              command.schedule();
079            }
080
081            m_pressedLast = pressed;
082          }
083        });
084    return this;
085  }
086
087  /**
088   * Starts the given command whenever the condition changes from `true` to `false`.
089   *
090   * @param command the command to start
091   * @return this trigger, so calls can be chained
092   */
093  public Trigger onFalse(Command command) {
094    requireNonNullParam(command, "command", "onFalling");
095    m_loop.bind(
096        new Runnable() {
097          private boolean m_pressedLast = m_condition.getAsBoolean();
098
099          @Override
100          public void run() {
101            boolean pressed = m_condition.getAsBoolean();
102
103            if (m_pressedLast && !pressed) {
104              command.schedule();
105            }
106
107            m_pressedLast = pressed;
108          }
109        });
110    return this;
111  }
112
113  /**
114   * Starts the given command when the condition changes to `true` and cancels it when the condition
115   * changes to `false`.
116   *
117   * <p>Doesn't re-start the command if it ends while the condition is still `true`. If the command
118   * should restart, see {@link edu.wpi.first.wpilibj2.command.RepeatCommand}.
119   *
120   * @param command the command to start
121   * @return this trigger, so calls can be chained
122   */
123  public Trigger whileTrue(Command command) {
124    requireNonNullParam(command, "command", "whileHigh");
125    m_loop.bind(
126        new Runnable() {
127          private boolean m_pressedLast = m_condition.getAsBoolean();
128
129          @Override
130          public void run() {
131            boolean pressed = m_condition.getAsBoolean();
132
133            if (!m_pressedLast && pressed) {
134              command.schedule();
135            } else if (m_pressedLast && !pressed) {
136              command.cancel();
137            }
138
139            m_pressedLast = pressed;
140          }
141        });
142    return this;
143  }
144
145  /**
146   * Starts the given command when the condition changes to `false` and cancels it when the
147   * condition changes to `true`.
148   *
149   * <p>Doesn't re-start the command if it ends while the condition is still `false`. If the command
150   * should restart, see {@link edu.wpi.first.wpilibj2.command.RepeatCommand}.
151   *
152   * @param command the command to start
153   * @return this trigger, so calls can be chained
154   */
155  public Trigger whileFalse(Command command) {
156    requireNonNullParam(command, "command", "whileLow");
157    m_loop.bind(
158        new Runnable() {
159          private boolean m_pressedLast = m_condition.getAsBoolean();
160
161          @Override
162          public void run() {
163            boolean pressed = m_condition.getAsBoolean();
164
165            if (m_pressedLast && !pressed) {
166              command.schedule();
167            } else if (!m_pressedLast && pressed) {
168              command.cancel();
169            }
170
171            m_pressedLast = pressed;
172          }
173        });
174    return this;
175  }
176
177  /**
178   * Toggles a command when the condition changes from `false` to `true`.
179   *
180   * @param command the command to toggle
181   * @return this trigger, so calls can be chained
182   */
183  public Trigger toggleOnTrue(Command command) {
184    requireNonNullParam(command, "command", "toggleOnRising");
185    m_loop.bind(
186        new Runnable() {
187          private boolean m_pressedLast = m_condition.getAsBoolean();
188
189          @Override
190          public void run() {
191            boolean pressed = m_condition.getAsBoolean();
192
193            if (!m_pressedLast && pressed) {
194              if (command.isScheduled()) {
195                command.cancel();
196              } else {
197                command.schedule();
198              }
199            }
200
201            m_pressedLast = pressed;
202          }
203        });
204    return this;
205  }
206
207  /**
208   * Toggles a command when the condition changes from `true` to `false`.
209   *
210   * @param command the command to toggle
211   * @return this trigger, so calls can be chained
212   */
213  public Trigger toggleOnFalse(Command command) {
214    requireNonNullParam(command, "command", "toggleOnFalling");
215    m_loop.bind(
216        new Runnable() {
217          private boolean m_pressedLast = m_condition.getAsBoolean();
218
219          @Override
220          public void run() {
221            boolean pressed = m_condition.getAsBoolean();
222
223            if (m_pressedLast && !pressed) {
224              if (command.isScheduled()) {
225                command.cancel();
226              } else {
227                command.schedule();
228              }
229            }
230
231            m_pressedLast = pressed;
232          }
233        });
234    return this;
235  }
236
237  /**
238   * Starts the given command whenever the trigger just becomes active.
239   *
240   * @param command the command to start
241   * @return this trigger, so calls can be chained
242   * @deprecated Use {@link #onTrue(Command)} instead.
243   */
244  @Deprecated
245  public Trigger whenActive(final Command command) {
246    requireNonNullParam(command, "command", "whenActive");
247
248    m_loop.bind(
249        new Runnable() {
250          private boolean m_pressedLast = m_condition.getAsBoolean();
251
252          @Override
253          public void run() {
254            boolean pressed = m_condition.getAsBoolean();
255
256            if (!m_pressedLast && pressed) {
257              command.schedule();
258            }
259
260            m_pressedLast = pressed;
261          }
262        });
263    return this;
264  }
265
266  /**
267   * Runs the given runnable whenever the trigger just becomes active.
268   *
269   * @param toRun the runnable to run
270   * @param requirements the required subsystems
271   * @return this trigger, so calls can be chained
272   * @deprecated Replace with {@link #onTrue(Command)}, creating the InstantCommand manually
273   */
274  @Deprecated
275  public Trigger whenActive(final Runnable toRun, Subsystem... requirements) {
276    return whenActive(new InstantCommand(toRun, requirements));
277  }
278
279  /**
280   * Constantly starts the given command while the button is held.
281   *
282   * <p>{@link Command#schedule()} will be called repeatedly while the trigger is active, and will
283   * be canceled when the trigger becomes inactive.
284   *
285   * @param command the command to start
286   * @return this trigger, so calls can be chained
287   * @deprecated Use {@link #whileTrue(Command)} with {@link
288   *     edu.wpi.first.wpilibj2.command.RepeatCommand RepeatCommand}, or bind {@link
289   *     Command#schedule() command::schedule} to {@link BooleanEvent#ifHigh(Runnable)} (passing no
290   *     requirements).
291   */
292  @Deprecated
293  public Trigger whileActiveContinuous(final Command command) {
294    requireNonNullParam(command, "command", "whileActiveContinuous");
295
296    m_loop.bind(
297        new Runnable() {
298          private boolean m_pressedLast = m_condition.getAsBoolean();
299
300          @Override
301          public void run() {
302            boolean pressed = m_condition.getAsBoolean();
303
304            if (pressed) {
305              command.schedule();
306            } else if (m_pressedLast) {
307              command.cancel();
308            }
309
310            m_pressedLast = pressed;
311          }
312        });
313
314    return this;
315  }
316
317  /**
318   * Constantly runs the given runnable while the button is held.
319   *
320   * @param toRun the runnable to run
321   * @param requirements the required subsystems
322   * @return this trigger, so calls can be chained
323   * @deprecated Use {@link #whileTrue(Command)} and construct a RunCommand manually
324   */
325  @Deprecated
326  public Trigger whileActiveContinuous(final Runnable toRun, Subsystem... requirements) {
327    return whileActiveContinuous(new InstantCommand(toRun, requirements));
328  }
329
330  /**
331   * Starts the given command when the trigger initially becomes active, and ends it when it becomes
332   * inactive, but does not re-start it in-between.
333   *
334   * @param command the command to start
335   * @return this trigger, so calls can be chained
336   * @deprecated Use {@link #whileTrue(Command)} instead.
337   */
338  @Deprecated
339  public Trigger whileActiveOnce(final Command command) {
340    requireNonNullParam(command, "command", "whileActiveOnce");
341
342    m_loop.bind(
343        new Runnable() {
344          private boolean m_pressedLast = m_condition.getAsBoolean();
345
346          @Override
347          public void run() {
348            boolean pressed = m_condition.getAsBoolean();
349
350            if (!m_pressedLast && pressed) {
351              command.schedule();
352            } else if (m_pressedLast && !pressed) {
353              command.cancel();
354            }
355
356            m_pressedLast = pressed;
357          }
358        });
359    return this;
360  }
361
362  /**
363   * Starts the command when the trigger becomes inactive.
364   *
365   * @param command the command to start
366   * @return this trigger, so calls can be chained
367   * @deprecated Use {@link #onFalse(Command)} instead.
368   */
369  @Deprecated
370  public Trigger whenInactive(final Command command) {
371    requireNonNullParam(command, "command", "whenInactive");
372
373    m_loop.bind(
374        new Runnable() {
375          private boolean m_pressedLast = m_condition.getAsBoolean();
376
377          @Override
378          public void run() {
379            boolean pressed = m_condition.getAsBoolean();
380
381            if (m_pressedLast && !pressed) {
382              command.schedule();
383            }
384
385            m_pressedLast = pressed;
386          }
387        });
388
389    return this;
390  }
391
392  /**
393   * Runs the given runnable when the trigger becomes inactive.
394   *
395   * @param toRun the runnable to run
396   * @param requirements the required subsystems
397   * @return this trigger, so calls can be chained
398   * @deprecated Construct the InstantCommand manually and replace with {@link #onFalse(Command)}
399   */
400  @Deprecated
401  public Trigger whenInactive(final Runnable toRun, Subsystem... requirements) {
402    return whenInactive(new InstantCommand(toRun, requirements));
403  }
404
405  /**
406   * Toggles a command when the trigger becomes active.
407   *
408   * @param command the command to toggle
409   * @return this trigger, so calls can be chained
410   * @deprecated Use {@link #toggleOnTrue(Command)} instead.
411   */
412  @Deprecated
413  public Trigger toggleWhenActive(final Command command) {
414    requireNonNullParam(command, "command", "toggleWhenActive");
415
416    m_loop.bind(
417        new Runnable() {
418          private boolean m_pressedLast = m_condition.getAsBoolean();
419
420          @Override
421          public void run() {
422            boolean pressed = m_condition.getAsBoolean();
423
424            if (!m_pressedLast && pressed) {
425              if (command.isScheduled()) {
426                command.cancel();
427              } else {
428                command.schedule();
429              }
430            }
431
432            m_pressedLast = pressed;
433          }
434        });
435
436    return this;
437  }
438
439  /**
440   * Cancels a command when the trigger becomes active.
441   *
442   * @param command the command to cancel
443   * @return this trigger, so calls can be chained
444   * @deprecated Instead, pass this as an end condition to {@link Command#until(BooleanSupplier)}.
445   */
446  @Deprecated
447  public Trigger cancelWhenActive(final Command command) {
448    requireNonNullParam(command, "command", "cancelWhenActive");
449
450    m_loop.bind(
451        new Runnable() {
452          private boolean m_pressedLast = m_condition.getAsBoolean();
453
454          @Override
455          public void run() {
456            boolean pressed = m_condition.getAsBoolean();
457
458            if (!m_pressedLast && pressed) {
459              command.cancel();
460            }
461
462            m_pressedLast = pressed;
463          }
464        });
465
466    return this;
467  }
468
469  @Override
470  public boolean getAsBoolean() {
471    return m_condition.getAsBoolean();
472  }
473
474  /**
475   * Composes two triggers with logical AND.
476   *
477   * @param trigger the condition to compose with
478   * @return A trigger which is active when both component triggers are active.
479   */
480  public Trigger and(BooleanSupplier trigger) {
481    return new Trigger(() -> m_condition.getAsBoolean() && trigger.getAsBoolean());
482  }
483
484  /**
485   * Composes two triggers with logical OR.
486   *
487   * @param trigger the condition to compose with
488   * @return A trigger which is active when either component trigger is active.
489   */
490  public Trigger or(BooleanSupplier trigger) {
491    return new Trigger(() -> m_condition.getAsBoolean() || trigger.getAsBoolean());
492  }
493
494  /**
495   * Creates a new trigger that is active when this trigger is inactive, i.e. that acts as the
496   * negation of this trigger.
497   *
498   * @return the negated trigger
499   */
500  public Trigger negate() {
501    return new Trigger(() -> !m_condition.getAsBoolean());
502  }
503
504  /**
505   * Creates a new debounced trigger from this trigger - it will become active when this trigger has
506   * been active for longer than the specified period.
507   *
508   * @param seconds The debounce period.
509   * @return The debounced trigger (rising edges debounced only)
510   */
511  public Trigger debounce(double seconds) {
512    return debounce(seconds, Debouncer.DebounceType.kRising);
513  }
514
515  /**
516   * Creates a new debounced trigger from this trigger - it will become active when this trigger has
517   * been active for longer than the specified period.
518   *
519   * @param seconds The debounce period.
520   * @param type The debounce type.
521   * @return The debounced trigger.
522   */
523  public Trigger debounce(double seconds, Debouncer.DebounceType type) {
524    return new Trigger(
525        new BooleanSupplier() {
526          final Debouncer m_debouncer = new Debouncer(seconds, type);
527
528          @Override
529          public boolean getAsBoolean() {
530            return m_debouncer.calculate(m_condition.getAsBoolean());
531          }
532        });
533  }
534}