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.math.controller; 006 007import edu.wpi.first.math.MathSharedStore; 008import edu.wpi.first.math.MathUsageId; 009import edu.wpi.first.math.MathUtil; 010import edu.wpi.first.math.trajectory.TrapezoidProfile; 011import edu.wpi.first.util.sendable.Sendable; 012import edu.wpi.first.util.sendable.SendableBuilder; 013import edu.wpi.first.util.sendable.SendableRegistry; 014 015/** 016 * Implements a PID control loop whose setpoint is constrained by a trapezoid profile. Users should 017 * call reset() when they first start running the controller to avoid unwanted behavior. 018 */ 019public class ProfiledPIDController implements Sendable { 020 private static int instances; 021 022 private PIDController m_controller; 023 private double m_minimumInput; 024 private double m_maximumInput; 025 private TrapezoidProfile.State m_goal = new TrapezoidProfile.State(); 026 private TrapezoidProfile.State m_setpoint = new TrapezoidProfile.State(); 027 private TrapezoidProfile.Constraints m_constraints; 028 029 /** 030 * Allocates a ProfiledPIDController with the given constants for Kp, Ki, and Kd. 031 * 032 * @param Kp The proportional coefficient. 033 * @param Ki The integral coefficient. 034 * @param Kd The derivative coefficient. 035 * @param constraints Velocity and acceleration constraints for goal. 036 */ 037 public ProfiledPIDController( 038 double Kp, double Ki, double Kd, TrapezoidProfile.Constraints constraints) { 039 this(Kp, Ki, Kd, constraints, 0.02); 040 } 041 042 /** 043 * Allocates a ProfiledPIDController with the given constants for Kp, Ki, and Kd. 044 * 045 * @param Kp The proportional coefficient. 046 * @param Ki The integral coefficient. 047 * @param Kd The derivative coefficient. 048 * @param constraints Velocity and acceleration constraints for goal. 049 * @param period The period between controller updates in seconds. The default is 0.02 seconds. 050 */ 051 public ProfiledPIDController( 052 double Kp, double Ki, double Kd, TrapezoidProfile.Constraints constraints, double period) { 053 m_controller = new PIDController(Kp, Ki, Kd, period); 054 m_constraints = constraints; 055 instances++; 056 057 SendableRegistry.add(this, "ProfiledPIDController", instances); 058 MathSharedStore.reportUsage(MathUsageId.kController_ProfiledPIDController, instances); 059 } 060 061 /** 062 * Sets the PID Controller gain parameters. 063 * 064 * <p>Sets the proportional, integral, and differential coefficients. 065 * 066 * @param Kp Proportional coefficient 067 * @param Ki Integral coefficient 068 * @param Kd Differential coefficient 069 */ 070 public void setPID(double Kp, double Ki, double Kd) { 071 m_controller.setPID(Kp, Ki, Kd); 072 } 073 074 /** 075 * Sets the proportional coefficient of the PID controller gain. 076 * 077 * @param Kp proportional coefficient 078 */ 079 public void setP(double Kp) { 080 m_controller.setP(Kp); 081 } 082 083 /** 084 * Sets the integral coefficient of the PID controller gain. 085 * 086 * @param Ki integral coefficient 087 */ 088 public void setI(double Ki) { 089 m_controller.setI(Ki); 090 } 091 092 /** 093 * Sets the differential coefficient of the PID controller gain. 094 * 095 * @param Kd differential coefficient 096 */ 097 public void setD(double Kd) { 098 m_controller.setD(Kd); 099 } 100 101 /** 102 * Gets the proportional coefficient. 103 * 104 * @return proportional coefficient 105 */ 106 public double getP() { 107 return m_controller.getP(); 108 } 109 110 /** 111 * Gets the integral coefficient. 112 * 113 * @return integral coefficient 114 */ 115 public double getI() { 116 return m_controller.getI(); 117 } 118 119 /** 120 * Gets the differential coefficient. 121 * 122 * @return differential coefficient 123 */ 124 public double getD() { 125 return m_controller.getD(); 126 } 127 128 /** 129 * Gets the period of this controller. 130 * 131 * @return The period of the controller. 132 */ 133 public double getPeriod() { 134 return m_controller.getPeriod(); 135 } 136 137 /** 138 * Returns the position tolerance of this controller. 139 * 140 * @return the position tolerance of the controller. 141 */ 142 public double getPositionTolerance() { 143 return m_controller.getPositionTolerance(); 144 } 145 146 /** 147 * Returns the velocity tolerance of this controller. 148 * 149 * @return the velocity tolerance of the controller. 150 */ 151 public double getVelocityTolerance() { 152 return m_controller.getVelocityTolerance(); 153 } 154 155 /** 156 * Sets the goal for the ProfiledPIDController. 157 * 158 * @param goal The desired goal state. 159 */ 160 public void setGoal(TrapezoidProfile.State goal) { 161 m_goal = goal; 162 } 163 164 /** 165 * Sets the goal for the ProfiledPIDController. 166 * 167 * @param goal The desired goal position. 168 */ 169 public void setGoal(double goal) { 170 m_goal = new TrapezoidProfile.State(goal, 0); 171 } 172 173 /** 174 * Gets the goal for the ProfiledPIDController. 175 * 176 * @return The goal. 177 */ 178 public TrapezoidProfile.State getGoal() { 179 return m_goal; 180 } 181 182 /** 183 * Returns true if the error is within the tolerance of the error. 184 * 185 * <p>This will return false until at least one input value has been computed. 186 * 187 * @return True if the error is within the tolerance of the error. 188 */ 189 public boolean atGoal() { 190 return atSetpoint() && m_goal.equals(m_setpoint); 191 } 192 193 /** 194 * Set velocity and acceleration constraints for goal. 195 * 196 * @param constraints Velocity and acceleration constraints for goal. 197 */ 198 public void setConstraints(TrapezoidProfile.Constraints constraints) { 199 m_constraints = constraints; 200 } 201 202 /** 203 * Returns the current setpoint of the ProfiledPIDController. 204 * 205 * @return The current setpoint. 206 */ 207 public TrapezoidProfile.State getSetpoint() { 208 return m_setpoint; 209 } 210 211 /** 212 * Returns true if the error is within the tolerance of the error. 213 * 214 * <p>This will return false until at least one input value has been computed. 215 * 216 * @return True if the error is within the tolerance of the error. 217 */ 218 public boolean atSetpoint() { 219 return m_controller.atSetpoint(); 220 } 221 222 /** 223 * Enables continuous input. 224 * 225 * <p>Rather then using the max and min input range as constraints, it considers them to be the 226 * same point and automatically calculates the shortest route to the setpoint. 227 * 228 * @param minimumInput The minimum value expected from the input. 229 * @param maximumInput The maximum value expected from the input. 230 */ 231 public void enableContinuousInput(double minimumInput, double maximumInput) { 232 m_controller.enableContinuousInput(minimumInput, maximumInput); 233 m_minimumInput = minimumInput; 234 m_maximumInput = maximumInput; 235 } 236 237 /** Disables continuous input. */ 238 public void disableContinuousInput() { 239 m_controller.disableContinuousInput(); 240 } 241 242 /** 243 * Sets the minimum and maximum values for the integrator. 244 * 245 * <p>When the cap is reached, the integrator value is added to the controller output rather than 246 * the integrator value times the integral gain. 247 * 248 * @param minimumIntegral The minimum value of the integrator. 249 * @param maximumIntegral The maximum value of the integrator. 250 */ 251 public void setIntegratorRange(double minimumIntegral, double maximumIntegral) { 252 m_controller.setIntegratorRange(minimumIntegral, maximumIntegral); 253 } 254 255 /** 256 * Sets the error which is considered tolerable for use with atSetpoint(). 257 * 258 * @param positionTolerance Position error which is tolerable. 259 */ 260 public void setTolerance(double positionTolerance) { 261 setTolerance(positionTolerance, Double.POSITIVE_INFINITY); 262 } 263 264 /** 265 * Sets the error which is considered tolerable for use with atSetpoint(). 266 * 267 * @param positionTolerance Position error which is tolerable. 268 * @param velocityTolerance Velocity error which is tolerable. 269 */ 270 public void setTolerance(double positionTolerance, double velocityTolerance) { 271 m_controller.setTolerance(positionTolerance, velocityTolerance); 272 } 273 274 /** 275 * Returns the difference between the setpoint and the measurement. 276 * 277 * @return The error. 278 */ 279 public double getPositionError() { 280 return m_controller.getPositionError(); 281 } 282 283 /** 284 * Returns the change in error per second. 285 * 286 * @return The change in error per second. 287 */ 288 public double getVelocityError() { 289 return m_controller.getVelocityError(); 290 } 291 292 /** 293 * Returns the next output of the PID controller. 294 * 295 * @param measurement The current measurement of the process variable. 296 * @return The controller's next output. 297 */ 298 public double calculate(double measurement) { 299 if (m_controller.isContinuousInputEnabled()) { 300 // Get error which is the smallest distance between goal and measurement 301 double errorBound = (m_maximumInput - m_minimumInput) / 2.0; 302 double goalMinDistance = 303 MathUtil.inputModulus(m_goal.position - measurement, -errorBound, errorBound); 304 double setpointMinDistance = 305 MathUtil.inputModulus(m_setpoint.position - measurement, -errorBound, errorBound); 306 307 // Recompute the profile goal with the smallest error, thus giving the shortest path. The goal 308 // may be outside the input range after this operation, but that's OK because the controller 309 // will still go there and report an error of zero. In other words, the setpoint only needs to 310 // be offset from the measurement by the input range modulus; they don't need to be equal. 311 m_goal.position = goalMinDistance + measurement; 312 m_setpoint.position = setpointMinDistance + measurement; 313 } 314 315 var profile = new TrapezoidProfile(m_constraints, m_goal, m_setpoint); 316 m_setpoint = profile.calculate(getPeriod()); 317 return m_controller.calculate(measurement, m_setpoint.position); 318 } 319 320 /** 321 * Returns the next output of the PID controller. 322 * 323 * @param measurement The current measurement of the process variable. 324 * @param goal The new goal of the controller. 325 * @return The controller's next output. 326 */ 327 public double calculate(double measurement, TrapezoidProfile.State goal) { 328 setGoal(goal); 329 return calculate(measurement); 330 } 331 332 /** 333 * Returns the next output of the PIDController. 334 * 335 * @param measurement The current measurement of the process variable. 336 * @param goal The new goal of the controller. 337 * @return The controller's next output. 338 */ 339 public double calculate(double measurement, double goal) { 340 setGoal(goal); 341 return calculate(measurement); 342 } 343 344 /** 345 * Returns the next output of the PID controller. 346 * 347 * @param measurement The current measurement of the process variable. 348 * @param goal The new goal of the controller. 349 * @param constraints Velocity and acceleration constraints for goal. 350 * @return The controller's next output. 351 */ 352 public double calculate( 353 double measurement, TrapezoidProfile.State goal, TrapezoidProfile.Constraints constraints) { 354 setConstraints(constraints); 355 return calculate(measurement, goal); 356 } 357 358 /** 359 * Reset the previous error and the integral term. 360 * 361 * @param measurement The current measured State of the system. 362 */ 363 public void reset(TrapezoidProfile.State measurement) { 364 m_controller.reset(); 365 m_setpoint = measurement; 366 } 367 368 /** 369 * Reset the previous error and the integral term. 370 * 371 * @param measuredPosition The current measured position of the system. 372 * @param measuredVelocity The current measured velocity of the system. 373 */ 374 public void reset(double measuredPosition, double measuredVelocity) { 375 reset(new TrapezoidProfile.State(measuredPosition, measuredVelocity)); 376 } 377 378 /** 379 * Reset the previous error and the integral term. 380 * 381 * @param measuredPosition The current measured position of the system. The velocity is assumed to 382 * be zero. 383 */ 384 public void reset(double measuredPosition) { 385 reset(measuredPosition, 0.0); 386 } 387 388 @Override 389 public void initSendable(SendableBuilder builder) { 390 builder.setSmartDashboardType("ProfiledPIDController"); 391 builder.addDoubleProperty("p", this::getP, this::setP); 392 builder.addDoubleProperty("i", this::getI, this::setI); 393 builder.addDoubleProperty("d", this::getD, this::setD); 394 builder.addDoubleProperty("goal", () -> getGoal().position, this::setGoal); 395 } 396}