|
Robot Core Documentation
|
Public Member Functions | |
| PIDController (double kp, double ki, double kd) | |
| PIDController (double kp, double ki, double kd, double period) | |
| void | setPID (double kp, double ki, double kd) |
| void | setP (double kp) |
| void | setI (double ki) |
| void | setD (double kd) |
| void | setIZone (double iZone) |
| double | getP () |
| double | getI () |
| double | getD () |
| double | getIZone () |
| double | getPeriod () |
| double | getPositionTolerance () |
| double | getVelocityTolerance () |
| void | setSetpoint (double setpoint) |
| double | getSetpoint () |
| boolean | atSetpoint () |
| void | enableContinuousInput (double minimumInput, double maximumInput) |
| void | disableContinuousInput () |
| boolean | isContinuousInputEnabled () |
| void | setIntegratorRange (double minimumIntegral, double maximumIntegral) |
| void | setTolerance (double positionTolerance) |
| void | setTolerance (double positionTolerance, double velocityTolerance) |
| double | getPositionError () |
| double | getVelocityError () |
| double | calculate (double measurement, double setpoint) |
| double | calculate (double measurement) |
| void | reset () |
| void | initSendable (SendableBuilder builder) |
Public Member Functions inherited from edu.wpi.first.util.sendable.Sendable | |
Implements a PID control loop.
| edu.wpi.first.math.controller.PIDController.PIDController | ( | double | kp, |
| double | ki, | ||
| double | kd ) |
Allocates a PIDController with the given constants for kp, ki, and kd and a default period of 0.02 seconds.
| kp | The proportional coefficient. |
| ki | The integral coefficient. |
| kd | The derivative coefficient. |
| IllegalArgumentException | if kp < 0 |
| IllegalArgumentException | if ki < 0 |
| IllegalArgumentException | if kd < 0 |
| edu.wpi.first.math.controller.PIDController.PIDController | ( | double | kp, |
| double | ki, | ||
| double | kd, | ||
| double | period ) |
Allocates a PIDController with the given constants for kp, ki, and kd.
| kp | The proportional coefficient. |
| ki | The integral coefficient. |
| kd | The derivative coefficient. |
| period | The period between controller updates in seconds. |
| IllegalArgumentException | if kp < 0 |
| IllegalArgumentException | if ki < 0 |
| IllegalArgumentException | if kd < 0 |
| IllegalArgumentException | if period <= 0 |
| boolean edu.wpi.first.math.controller.PIDController.atSetpoint | ( | ) |
Returns true if the error is within the tolerance of the setpoint.
This will return false until at least one input value has been computed.
| double edu.wpi.first.math.controller.PIDController.calculate | ( | double | measurement | ) |
Returns the next output of the PID controller.
| measurement | The current measurement of the process variable. |
| double edu.wpi.first.math.controller.PIDController.calculate | ( | double | measurement, |
| double | setpoint ) |
Returns the next output of the PID controller.
| measurement | The current measurement of the process variable. |
| setpoint | The new setpoint of the controller. |
| void edu.wpi.first.math.controller.PIDController.disableContinuousInput | ( | ) |
Disables continuous input.
| void edu.wpi.first.math.controller.PIDController.enableContinuousInput | ( | double | minimumInput, |
| double | maximumInput ) |
Enables continuous input.
Rather then using the max and min input range as constraints, it considers them to be the same point and automatically calculates the shortest route to the setpoint.
| minimumInput | The minimum value expected from the input. |
| maximumInput | The maximum value expected from the input. |
| double edu.wpi.first.math.controller.PIDController.getD | ( | ) |
Get the Differential coefficient.
| double edu.wpi.first.math.controller.PIDController.getI | ( | ) |
Get the Integral coefficient.
| double edu.wpi.first.math.controller.PIDController.getIZone | ( | ) |
Get the IZone range.
| double edu.wpi.first.math.controller.PIDController.getP | ( | ) |
Get the Proportional coefficient.
| double edu.wpi.first.math.controller.PIDController.getPeriod | ( | ) |
Returns the period of this controller.
| double edu.wpi.first.math.controller.PIDController.getPositionError | ( | ) |
Returns the difference between the setpoint and the measurement.
| double edu.wpi.first.math.controller.PIDController.getPositionTolerance | ( | ) |
Returns the position tolerance of this controller.
| double edu.wpi.first.math.controller.PIDController.getSetpoint | ( | ) |
Returns the current setpoint of the PIDController.
| double edu.wpi.first.math.controller.PIDController.getVelocityError | ( | ) |
Returns the velocity error.
| double edu.wpi.first.math.controller.PIDController.getVelocityTolerance | ( | ) |
Returns the velocity tolerance of this controller.
| void edu.wpi.first.math.controller.PIDController.initSendable | ( | SendableBuilder | builder | ) |
Initializes this Sendable object.
| builder | sendable builder |
Implements edu.wpi.first.util.sendable.Sendable.
| boolean edu.wpi.first.math.controller.PIDController.isContinuousInputEnabled | ( | ) |
Returns true if continuous input is enabled.
| void edu.wpi.first.math.controller.PIDController.reset | ( | ) |
Resets the previous error and the integral term.
| void edu.wpi.first.math.controller.PIDController.setD | ( | double | kd | ) |
Sets the Differential coefficient of the PID controller gain.
| kd | The differential coefficient. Must be >= 0. |
| void edu.wpi.first.math.controller.PIDController.setI | ( | double | ki | ) |
Sets the Integral coefficient of the PID controller gain.
| ki | The integral coefficient. Must be >= 0. |
| void edu.wpi.first.math.controller.PIDController.setIntegratorRange | ( | double | minimumIntegral, |
| double | maximumIntegral ) |
Sets the minimum and maximum values for the integrator.
When the cap is reached, the integrator value is added to the controller output rather than the integrator value times the integral gain.
| minimumIntegral | The minimum value of the integrator. |
| maximumIntegral | The maximum value of the integrator. |
| void edu.wpi.first.math.controller.PIDController.setIZone | ( | double | iZone | ) |
Sets the IZone range. When the absolute value of the position error is greater than IZone, the total accumulated error will reset to zero, disabling integral gain until the absolute value of the position error is less than IZone. This is used to prevent integral windup. Must be non-negative. Passing a value of zero will effectively disable integral gain. Passing a value of Double#POSITIVE_INFINITY disables IZone functionality.
| iZone | Maximum magnitude of error to allow integral control. |
| IllegalArgumentException | if iZone < 0 |
| void edu.wpi.first.math.controller.PIDController.setP | ( | double | kp | ) |
Sets the Proportional coefficient of the PID controller gain.
| kp | The proportional coefficient. Must be >= 0. |
| void edu.wpi.first.math.controller.PIDController.setPID | ( | double | kp, |
| double | ki, | ||
| double | kd ) |
Sets the PID Controller gain parameters.
Set the proportional, integral, and differential coefficients.
| kp | The proportional coefficient. |
| ki | The integral coefficient. |
| kd | The derivative coefficient. |
| void edu.wpi.first.math.controller.PIDController.setSetpoint | ( | double | setpoint | ) |
Sets the setpoint for the PIDController.
| setpoint | The desired setpoint. |
| void edu.wpi.first.math.controller.PIDController.setTolerance | ( | double | positionTolerance | ) |
Sets the error which is considered tolerable for use with atSetpoint().
| positionTolerance | Position error which is tolerable. |
| void edu.wpi.first.math.controller.PIDController.setTolerance | ( | double | positionTolerance, |
| double | velocityTolerance ) |
Sets the error which is considered tolerable for use with atSetpoint().
| positionTolerance | Position error which is tolerable. |
| velocityTolerance | Velocity error which is tolerable. |