PIDController

class wpimath.controller.PIDController(Kp: float, Ki: float, Kd: float, period: wpimath.units.seconds = 0.02)

Bases: Sendable

Implements a PID control loop.

Allocates a PIDController with the given constants for Kp, Ki, and Kd.

Parameters:
  • Kp – The proportional coefficient. Must be >= 0.

  • Ki – The integral coefficient. Must be >= 0.

  • Kd – The derivative coefficient. Must be >= 0.

  • period – The period between controller updates in seconds. The default is 20 milliseconds. Must be positive.

atSetpoint() bool

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.

calculate(*args, **kwargs)

Overloaded function.

  1. calculate(self: wpimath._controls._controls.controller.PIDController, measurement: float) -> float

Returns the next output of the PID controller.

Parameters:

measurement – The current measurement of the process variable.

  1. calculate(self: wpimath._controls._controls.controller.PIDController, measurement: float, setpoint: float) -> float

Returns the next output of the PID controller.

Parameters:
  • measurement – The current measurement of the process variable.

  • setpoint – The new setpoint of the controller.

disableContinuousInput() None

Disables continuous input.

enableContinuousInput(minimumInput: float, maximumInput: float) None

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.

Parameters:
  • minimumInput – The minimum value expected from the input.

  • maximumInput – The maximum value expected from the input.

getD() float

Gets the differential coefficient.

Returns:

differential coefficient

getI() float

Gets the integral coefficient.

Returns:

integral coefficient

getIZone() float

Get the IZone range.

Returns:

Maximum magnitude of error to allow integral control.

getP() float

Gets the proportional coefficient.

Returns:

proportional coefficient

getPeriod() wpimath.units.seconds

Gets the period of this controller.

Returns:

The period of the controller.

getPositionError() float

Returns the difference between the setpoint and the measurement.

getPositionTolerance() float

Gets the position tolerance of this controller.

Returns:

The position tolerance of the controller.

getSetpoint() float

Returns the current setpoint of the PIDController.

Returns:

The current setpoint.

getVelocityError() float

Returns the velocity error.

getVelocityTolerance() float

Gets the velocity tolerance of this controller.

Returns:

The velocity tolerance of the controller.

initSendable(builder: wpiutil._wpiutil.SendableBuilder) None
isContinuousInputEnabled() bool

Returns true if continuous input is enabled.

reset() None

Reset the previous error, the integral term, and disable the controller.

setD(Kd: float) None

Sets the differential coefficient of the PID controller gain.

Parameters:

Kd – The differential coefficient. Must be >= 0.

setI(Ki: float) None

Sets the integral coefficient of the PID controller gain.

Parameters:

Ki – The integral coefficient. Must be >= 0.

setIZone(iZone: float) None

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 infinity disables IZone functionality.

Parameters:

iZone – Maximum magnitude of error to allow integral control. Must be >= 0.

setIntegratorRange(minimumIntegral: float, maximumIntegral: float) None

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.

Parameters:
  • minimumIntegral – The minimum value of the integrator.

  • maximumIntegral – The maximum value of the integrator.

setP(Kp: float) None

Sets the proportional coefficient of the PID controller gain.

Parameters:

Kp – The proportional coefficient. Must be >= 0.

setPID(Kp: float, Ki: float, Kd: float) None

Sets the PID Controller gain parameters.

Sets the proportional, integral, and differential coefficients.

Parameters:
  • Kp – The proportional coefficient. Must be >= 0.

  • Ki – The integral coefficient. Must be >= 0.

  • Kd – The differential coefficient. Must be >= 0.

setSetpoint(setpoint: float) None

Sets the setpoint for the PIDController.

Parameters:

setpoint – The desired setpoint.

setTolerance(positionTolerance: float, velocityTolerance: float = inf) None

Sets the error which is considered tolerable for use with AtSetpoint().

Parameters:
  • positionTolerance – Position error which is tolerable.

  • velocityTolerance – Velocity error which is tolerable.