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