001/*----------------------------------------------------------------------------*/
002/* Copyright (c) FIRST 2008-2017. All Rights Reserved.                        */
003/* Open Source Software - may be modified and shared by FRC teams. The code   */
004/* must be accompanied by the FIRST BSD license file in the root directory of */
005/* the project.                                                               */
006/*----------------------------------------------------------------------------*/
007
008package edu.wpi.first.wpilibj.command;
009
010import edu.wpi.first.wpilibj.PIDController;
011import edu.wpi.first.wpilibj.PIDOutput;
012import edu.wpi.first.wpilibj.PIDSource;
013import edu.wpi.first.wpilibj.PIDSourceType;
014import edu.wpi.first.wpilibj.Sendable;
015import edu.wpi.first.wpilibj.tables.ITable;
016
017/**
018 * This class defines a {@link Command} which interacts heavily with a PID loop.
019 *
020 * <p> It provides some convenience methods to run an internal {@link PIDController} . It will also
021 * start and stop said {@link PIDController} when the {@link PIDCommand} is first initialized and
022 * ended/interrupted. </p>
023 */
024public abstract class PIDCommand extends Command implements Sendable {
025
026  /**
027   * The internal {@link PIDController}.
028   */
029  private final PIDController m_controller;
030  /**
031   * An output which calls {@link PIDCommand#usePIDOutput(double)}.
032   */
033  private final PIDOutput m_output = this::usePIDOutput;
034  /**
035   * A source which calls {@link PIDCommand#returnPIDInput()}.
036   */
037  private final PIDSource m_source = new PIDSource() {
038    public void setPIDSourceType(PIDSourceType pidSource) {
039    }
040
041    public PIDSourceType getPIDSourceType() {
042      return PIDSourceType.kDisplacement;
043    }
044
045    public double pidGet() {
046      return returnPIDInput();
047    }
048  };
049
050  /**
051   * Instantiates a {@link PIDCommand} that will use the given p, i and d values.
052   *
053   * @param name the name of the command
054   * @param p    the proportional value
055   * @param i    the integral value
056   * @param d    the derivative value
057   */
058  @SuppressWarnings("ParameterName")
059  public PIDCommand(String name, double p, double i, double d) {
060    super(name);
061    m_controller = new PIDController(p, i, d, m_source, m_output);
062  }
063
064  /**
065   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will also space
066   * the time between PID loop calculations to be equal to the given period.
067   *
068   * @param name   the name
069   * @param p      the proportional value
070   * @param i      the integral value
071   * @param d      the derivative value
072   * @param period the time (in seconds) between calculations
073   */
074  @SuppressWarnings("ParameterName")
075  public PIDCommand(String name, double p, double i, double d, double period) {
076    super(name);
077    m_controller = new PIDController(p, i, d, m_source, m_output, period);
078  }
079
080  /**
081   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
082   * class name as its name.
083   *
084   * @param p the proportional value
085   * @param i the integral value
086   * @param d the derivative value
087   */
088  @SuppressWarnings("ParameterName")
089  public PIDCommand(double p, double i, double d) {
090    m_controller = new PIDController(p, i, d, m_source, m_output);
091  }
092
093  /**
094   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
095   * class name as its name.. It will also space the time between PID loop calculations to be equal
096   * to the given period.
097   *
098   * @param p      the proportional value
099   * @param i      the integral value
100   * @param d      the derivative value
101   * @param period the time (in seconds) between calculations
102   */
103  @SuppressWarnings("ParameterName")
104  public PIDCommand(double p, double i, double d, double period) {
105    m_controller = new PIDController(p, i, d, m_source, m_output, period);
106  }
107
108  /**
109   * Returns the {@link PIDController} used by this {@link PIDCommand}. Use this if you would like
110   * to fine tune the pid loop.
111   *
112   * @return the {@link PIDController} used by this {@link PIDCommand}
113   */
114  protected PIDController getPIDController() {
115    return m_controller;
116  }
117
118  @Override
119  @SuppressWarnings("MethodName")
120  void _initialize() {
121    m_controller.enable();
122  }
123
124  @Override
125  @SuppressWarnings("MethodName")
126  void _end() {
127    m_controller.disable();
128  }
129
130  @Override
131  @SuppressWarnings("MethodName")
132  void _interrupted() {
133    _end();
134  }
135
136  /**
137   * Adds the given value to the setpoint. If {@link PIDCommand#setInputRange(double, double)
138   * setInputRange(...)} was used, then the bounds will still be honored by this method.
139   *
140   * @param deltaSetpoint the change in the setpoint
141   */
142  public void setSetpointRelative(double deltaSetpoint) {
143    setSetpoint(getSetpoint() + deltaSetpoint);
144  }
145
146  /**
147   * Sets the setpoint to the given value. If {@link PIDCommand#setInputRange(double, double)
148   * setInputRange(...)} was called, then the given setpoint will be trimmed to fit within the
149   * range.
150   *
151   * @param setpoint the new setpoint
152   */
153  protected void setSetpoint(double setpoint) {
154    m_controller.setSetpoint(setpoint);
155  }
156
157  /**
158   * Returns the setpoint.
159   *
160   * @return the setpoint
161   */
162  protected double getSetpoint() {
163    return m_controller.getSetpoint();
164  }
165
166  /**
167   * Returns the current position.
168   *
169   * @return the current position
170   */
171  protected double getPosition() {
172    return returnPIDInput();
173  }
174
175  /**
176   * Sets the maximum and minimum values expected from the input and setpoint.
177   *
178   * @param minimumInput the minimum value expected from the input and setpoint
179   * @param maximumInput the maximum value expected from the input and setpoint
180   */
181  protected void setInputRange(double minimumInput, double maximumInput) {
182    m_controller.setInputRange(minimumInput, maximumInput);
183  }
184
185  /**
186   * Returns the input for the pid loop.
187   *
188   * <p>It returns the input for the pid loop, so if this command was based off of a gyro, then it
189   * should return the angle of the gyro.
190   *
191   * <p>All subclasses of {@link PIDCommand} must override this method.
192   *
193   * <p>This method will be called in a different thread then the {@link Scheduler} thread.
194   *
195   * @return the value the pid loop should use as input
196   */
197  protected abstract double returnPIDInput();
198
199  /**
200   * Uses the value that the pid loop calculated. The calculated value is the "output" parameter.
201   * This method is a good time to set motor values, maybe something along the lines of
202   * <code>driveline.tankDrive(output, -output)</code>
203   *
204   * <p>All subclasses of {@link PIDCommand} must override this method.
205   *
206   * <p>This method will be called in a different thread then the {@link Scheduler} thread.
207   *
208   * @param output the value the pid loop calculated
209   */
210  protected abstract void usePIDOutput(double output);
211
212  public String getSmartDashboardType() {
213    return "PIDCommand";
214  }
215
216  public void initTable(ITable table) {
217    m_controller.initTable(table);
218    super.initTable(table);
219  }
220}