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;
006
007import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
008
009import edu.wpi.first.math.controller.PIDController;
010
011/**
012 * A subsystem that uses a {@link PIDController} to control an output. The controller is run
013 * synchronously from the subsystem's periodic() method.
014 *
015 * <p>This class is provided by the NewCommands VendorDep
016 */
017public abstract class PIDSubsystem extends SubsystemBase {
018  /** PID controller. */
019  protected final PIDController m_controller;
020
021  /** Whether PID controller output is enabled. */
022  protected boolean m_enabled;
023
024  /**
025   * Creates a new PIDSubsystem.
026   *
027   * @param controller the PIDController to use
028   * @param initialPosition the initial setpoint of the subsystem
029   */
030  @SuppressWarnings("this-escape")
031  public PIDSubsystem(PIDController controller, double initialPosition) {
032    m_controller = requireNonNullParam(controller, "controller", "PIDSubsystem");
033    setSetpoint(initialPosition);
034    addChild("PID Controller", m_controller);
035  }
036
037  /**
038   * Creates a new PIDSubsystem. Initial setpoint is zero.
039   *
040   * @param controller the PIDController to use
041   */
042  public PIDSubsystem(PIDController controller) {
043    this(controller, 0);
044  }
045
046  @Override
047  public void periodic() {
048    if (m_enabled) {
049      useOutput(m_controller.calculate(getMeasurement()), getSetpoint());
050    }
051  }
052
053  /**
054   * Returns the PIDController.
055   *
056   * @return The controller.
057   */
058  public PIDController getController() {
059    return m_controller;
060  }
061
062  /**
063   * Sets the setpoint for the subsystem.
064   *
065   * @param setpoint the setpoint for the subsystem
066   */
067  public final void setSetpoint(double setpoint) {
068    m_controller.setSetpoint(setpoint);
069  }
070
071  /**
072   * Returns the current setpoint of the subsystem.
073   *
074   * @return The current setpoint
075   */
076  public double getSetpoint() {
077    return m_controller.getSetpoint();
078  }
079
080  /**
081   * Uses the output from the PIDController.
082   *
083   * @param output the output of the PIDController
084   * @param setpoint the setpoint of the PIDController (for feedforward)
085   */
086  protected abstract void useOutput(double output, double setpoint);
087
088  /**
089   * Returns the measurement of the process variable used by the PIDController.
090   *
091   * @return the measurement of the process variable
092   */
093  protected abstract double getMeasurement();
094
095  /** Enables the PID control. Resets the controller. */
096  public void enable() {
097    m_enabled = true;
098    m_controller.reset();
099  }
100
101  /** Disables the PID control. Sets output to zero. */
102  public void disable() {
103    m_enabled = false;
104    useOutput(0, 0);
105  }
106
107  /**
108   * Returns whether the controller is enabled.
109   *
110   * @return Whether the controller is enabled.
111   */
112  public boolean isEnabled() {
113    return m_enabled;
114  }
115}