001/*----------------------------------------------------------------------------*/ 002/* Copyright (c) 2008-2018 FIRST. 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; 015 016/** 017 * This class is designed to handle the case where there is a {@link Subsystem} which uses a single 018 * {@link PIDController} almost constantly (for instance, an elevator which attempts to stay at a 019 * constant height). 020 * 021 * <p>It provides some convenience methods to run an internal {@link PIDController} . It also 022 * allows access to the internal {@link PIDController} in order to give total control to the 023 * programmer. 024 */ 025public abstract class PIDSubsystem extends Subsystem implements Sendable { 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 /** 036 * A source which calls {@link PIDCommand#returnPIDInput()}. 037 */ 038 private final PIDSource m_source = new PIDSource() { 039 public void setPIDSourceType(PIDSourceType pidSource) { 040 } 041 042 public PIDSourceType getPIDSourceType() { 043 return PIDSourceType.kDisplacement; 044 } 045 046 public double pidGet() { 047 return returnPIDInput(); 048 } 049 }; 050 051 /** 052 * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. 053 * 054 * @param name the name 055 * @param p the proportional value 056 * @param i the integral value 057 * @param d the derivative value 058 */ 059 @SuppressWarnings("ParameterName") 060 public PIDSubsystem(String name, double p, double i, double d) { 061 super(name); 062 m_controller = new PIDController(p, i, d, m_source, m_output); 063 addChild("PIDController", m_controller); 064 } 065 066 /** 067 * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. 068 * 069 * @param name the name 070 * @param p the proportional value 071 * @param i the integral value 072 * @param d the derivative value 073 * @param f the feed forward value 074 */ 075 @SuppressWarnings("ParameterName") 076 public PIDSubsystem(String name, double p, double i, double d, double f) { 077 super(name); 078 m_controller = new PIDController(p, i, d, f, m_source, m_output); 079 addChild("PIDController", m_controller); 080 } 081 082 /** 083 * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will also 084 * space the time between PID loop calculations to be equal to the given period. 085 * 086 * @param name the name 087 * @param p the proportional value 088 * @param i the integral value 089 * @param d the derivative value 090 * @param period the time (in seconds) between calculations 091 */ 092 @SuppressWarnings("ParameterName") 093 public PIDSubsystem(String name, double p, double i, double d, double f, double period) { 094 super(name); 095 m_controller = new PIDController(p, i, d, f, m_source, m_output, period); 096 addChild("PIDController", m_controller); 097 } 098 099 /** 100 * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will use the 101 * class name as its name. 102 * 103 * @param p the proportional value 104 * @param i the integral value 105 * @param d the derivative value 106 */ 107 @SuppressWarnings("ParameterName") 108 public PIDSubsystem(double p, double i, double d) { 109 m_controller = new PIDController(p, i, d, m_source, m_output); 110 addChild("PIDController", m_controller); 111 } 112 113 /** 114 * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will use the 115 * class name as its name. It will also space the time between PID loop calculations to be equal 116 * to the given period. 117 * 118 * @param p the proportional value 119 * @param i the integral value 120 * @param d the derivative value 121 * @param f the feed forward coefficient 122 * @param period the time (in seconds) between calculations 123 */ 124 @SuppressWarnings("ParameterName") 125 public PIDSubsystem(double p, double i, double d, double period, double f) { 126 m_controller = new PIDController(p, i, d, f, m_source, m_output, period); 127 addChild("PIDController", m_controller); 128 } 129 130 /** 131 * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will use the 132 * class name as its name. It will also space the time between PID loop calculations to be equal 133 * to the given period. 134 * 135 * @param p the proportional value 136 * @param i the integral value 137 * @param d the derivative value 138 * @param period the time (in seconds) between calculations 139 */ 140 @SuppressWarnings("ParameterName") 141 public PIDSubsystem(double p, double i, double d, double period) { 142 m_controller = new PIDController(p, i, d, m_source, m_output, period); 143 addChild("PIDController", m_controller); 144 } 145 146 /** 147 * Returns the {@link PIDController} used by this {@link PIDSubsystem}. Use this if you would like 148 * to fine tune the pid loop. 149 * 150 * @return the {@link PIDController} used by this {@link PIDSubsystem} 151 */ 152 public PIDController getPIDController() { 153 return m_controller; 154 } 155 156 157 /** 158 * Adds the given value to the setpoint. If {@link PIDSubsystem#setInputRange(double, double) 159 * setInputRange(...)} was used, then the bounds will still be honored by this method. 160 * 161 * @param deltaSetpoint the change in the setpoint 162 */ 163 public void setSetpointRelative(double deltaSetpoint) { 164 setSetpoint(getPosition() + deltaSetpoint); 165 } 166 167 /** 168 * Sets the setpoint to the given value. If {@link PIDSubsystem#setInputRange(double, double) 169 * setInputRange(...)} was called, then the given setpoint will be trimmed to fit within the 170 * range. 171 * 172 * @param setpoint the new setpoint 173 */ 174 public void setSetpoint(double setpoint) { 175 m_controller.setSetpoint(setpoint); 176 } 177 178 /** 179 * Returns the setpoint. 180 * 181 * @return the setpoint 182 */ 183 public double getSetpoint() { 184 return m_controller.getSetpoint(); 185 } 186 187 /** 188 * Returns the current position. 189 * 190 * @return the current position 191 */ 192 public double getPosition() { 193 return returnPIDInput(); 194 } 195 196 /** 197 * Sets the maximum and minimum values expected from the input. 198 * 199 * @param minimumInput the minimum value expected from the input 200 * @param maximumInput the maximum value expected from the output 201 */ 202 public void setInputRange(double minimumInput, double maximumInput) { 203 m_controller.setInputRange(minimumInput, maximumInput); 204 } 205 206 /** 207 * Sets the maximum and minimum values to write. 208 * 209 * @param minimumOutput the minimum value to write to the output 210 * @param maximumOutput the maximum value to write to the output 211 */ 212 public void setOutputRange(double minimumOutput, double maximumOutput) { 213 m_controller.setOutputRange(minimumOutput, maximumOutput); 214 } 215 216 /** 217 * Set the absolute error which is considered tolerable for use with OnTarget. The value is in the 218 * same range as the PIDInput values. 219 * 220 * @param t the absolute tolerance 221 */ 222 @SuppressWarnings("ParameterName") 223 public void setAbsoluteTolerance(double t) { 224 m_controller.setAbsoluteTolerance(t); 225 } 226 227 /** 228 * Set the percentage error which is considered tolerable for use with OnTarget. (Value of 15.0 == 229 * 15 percent). 230 * 231 * @param p the percent tolerance 232 */ 233 @SuppressWarnings("ParameterName") 234 public void setPercentTolerance(double p) { 235 m_controller.setPercentTolerance(p); 236 } 237 238 /** 239 * Return true if the error is within the percentage of the total input range, determined by 240 * setTolerance. This assumes that the maximum and minimum input were set using setInput. 241 * 242 * @return true if the error is less than the tolerance 243 */ 244 public boolean onTarget() { 245 return m_controller.onTarget(); 246 } 247 248 /** 249 * Returns the input for the pid loop. 250 * 251 * <p>It returns the input for the pid loop, so if this Subsystem was based off of a gyro, then 252 * it should return the angle of the gyro. 253 * 254 * <p>All subclasses of {@link PIDSubsystem} must override this method. 255 * 256 * @return the value the pid loop should use as input 257 */ 258 protected abstract double returnPIDInput(); 259 260 /** 261 * Uses the value that the pid loop calculated. The calculated value is the "output" parameter. 262 * This method is a good time to set motor values, maybe something along the lines of 263 * <code>driveline.tankDrive(output, -output)</code>. 264 * 265 * <p>All subclasses of {@link PIDSubsystem} must override this method. 266 * 267 * @param output the value the pid loop calculated 268 */ 269 protected abstract void usePIDOutput(double output); 270 271 /** 272 * Enables the internal {@link PIDController}. 273 */ 274 public void enable() { 275 m_controller.enable(); 276 } 277 278 /** 279 * Disables the internal {@link PIDController}. 280 */ 281 public void disable() { 282 m_controller.disable(); 283 } 284}