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.buttons;
006
007import edu.wpi.first.util.sendable.Sendable;
008import edu.wpi.first.util.sendable.SendableBuilder;
009import edu.wpi.first.wpilibj.command.Command;
010import edu.wpi.first.wpilibj.command.Scheduler;
011
012/**
013 * This class provides an easy way to link commands to inputs.
014 *
015 * <p>It is very easy to link a button to a command. For instance, you could link the trigger button
016 * of a joystick to a "score" command.
017 *
018 * <p>It is encouraged that teams write a subclass of Trigger if they want to have something unusual
019 * (for instance, if they want to react to the user holding a button while the robot is reading a
020 * certain sensor input). For this, they only have to write the {@link Trigger#get()} method to get
021 * the full functionality of the Trigger class.
022 */
023public abstract class Trigger implements Sendable {
024  private volatile boolean m_sendablePressed;
025
026  /**
027   * Returns whether or not the trigger is active.
028   *
029   * <p>This method will be called repeatedly a command is linked to the Trigger.
030   *
031   * @return whether or not the trigger condition is active.
032   */
033  public abstract boolean get();
034
035  /**
036   * Returns whether get() return true or the internal table for SmartDashboard use is pressed.
037   *
038   * @return whether get() return true or the internal table for SmartDashboard use is pressed.
039   */
040  private boolean grab() {
041    return get() || m_sendablePressed;
042  }
043
044  /**
045   * Starts the given command whenever the trigger just becomes active.
046   *
047   * @param command the command to start
048   */
049  public void whenActive(final Command command) {
050    new ButtonScheduler() {
051      private boolean m_pressedLast = grab();
052
053      @Override
054      public void execute() {
055        boolean pressed = grab();
056
057        if (!m_pressedLast && pressed) {
058          command.start();
059        }
060
061        m_pressedLast = pressed;
062      }
063    }.start();
064  }
065
066  /**
067   * Constantly starts the given command while the button is held.
068   *
069   * <p>{@link Command#start()} will be called repeatedly while the trigger is active, and will be
070   * canceled when the trigger becomes inactive.
071   *
072   * @param command the command to start
073   */
074  public void whileActive(final Command command) {
075    new ButtonScheduler() {
076      private boolean m_pressedLast = grab();
077
078      @Override
079      public void execute() {
080        boolean pressed = grab();
081
082        if (pressed) {
083          command.start();
084        } else if (m_pressedLast && !pressed) {
085          command.cancel();
086        }
087
088        m_pressedLast = pressed;
089      }
090    }.start();
091  }
092
093  /**
094   * Starts the command when the trigger becomes inactive.
095   *
096   * @param command the command to start
097   */
098  public void whenInactive(final Command command) {
099    new ButtonScheduler() {
100      private boolean m_pressedLast = grab();
101
102      @Override
103      public void execute() {
104        boolean pressed = grab();
105
106        if (m_pressedLast && !pressed) {
107          command.start();
108        }
109
110        m_pressedLast = pressed;
111      }
112    }.start();
113  }
114
115  /**
116   * Toggles a command when the trigger becomes active.
117   *
118   * @param command the command to toggle
119   */
120  public void toggleWhenActive(final Command command) {
121    new ButtonScheduler() {
122      private boolean m_pressedLast = grab();
123
124      @Override
125      public void execute() {
126        boolean pressed = grab();
127
128        if (!m_pressedLast && pressed) {
129          if (command.isRunning()) {
130            command.cancel();
131          } else {
132            command.start();
133          }
134        }
135
136        m_pressedLast = pressed;
137      }
138    }.start();
139  }
140
141  /**
142   * Cancels a command when the trigger becomes active.
143   *
144   * @param command the command to cancel
145   */
146  public void cancelWhenActive(final Command command) {
147    new ButtonScheduler() {
148      private boolean m_pressedLast = grab();
149
150      @Override
151      public void execute() {
152        boolean pressed = grab();
153
154        if (!m_pressedLast && pressed) {
155          command.cancel();
156        }
157
158        m_pressedLast = pressed;
159      }
160    }.start();
161  }
162
163  /**
164   * An internal class of {@link Trigger}. The user should ignore this, it is only public to
165   * interface between packages.
166   */
167  public abstract static class ButtonScheduler {
168    public abstract void execute();
169
170    public void start() {
171      Scheduler.getInstance().addButton(this);
172    }
173  }
174
175  @Override
176  public void initSendable(SendableBuilder builder) {
177    builder.setSmartDashboardType("Button");
178    builder.setSafeState(() -> m_sendablePressed = false);
179    builder.addBooleanProperty("pressed", this::grab, value -> m_sendablePressed = value);
180  }
181}