phoenix6.swerve.utility.phoenix_pid_controller

Module Contents

Functions

input_modulus(→ float)

Returns modulus of input.

phoenix6.swerve.utility.phoenix_pid_controller.input_modulus(input: float, minimum_input: float, maximum_input: float) float

Returns modulus of input.

Parameters:
  • input (float) – Input value to wrap.

  • minimum_input (float) – The minimum value expected from the input.

  • maximum_input – The maximum value expected from the input.

class phoenix6.swerve.utility.phoenix_pid_controller.PhoenixPIDController(Kp: float, Ki: float, Kd: float)

Phoenix-centric PID controller taken from WPI’s PIDController class.

This class differs from the WPI implementation by using explicit timestamps for integral/derivative calculations. Ideally, these timestamps come from the StatusSignal.

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

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

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

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

Sets the PID Controller gain parameters.

Sets the proportional, integral, and differential coefficients.

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

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

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

setP(Kp: float)

Sets the proportional coefficient of the PID controller gain.

Parameters:

Kp (float) – The proportional coefficient. Must be >= 0.

setI(Ki: float)

Sets the integral coefficient of the PID controller gain.

Parameters:

Ki (float) – The integral coefficient. Must be >= 0.

setD(Kd: float)

Sets the differential coefficient of the PID controller gain.

Parameters:

Kd (float) – The differential coefficient. Must be >= 0.

setIZone(iZone: float)

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 (float) – Maximum magnitude of error to allow integral control. Must be >= 0.

getP() float

Gets the proportional coefficient.

Returns:

proportional coefficient

Return type:

float

getI() float

Gets the integral coefficient.

Returns:

integral coefficient

Return type:

float

getD() float

Gets the differential coefficient.

Returns:

differential coefficient

Return type:

float

getIZone() float

Get the IZone range.

Returns:

Maximum magnitude of error to allow integral control

Return type:

float

getPositionTolerance() float

Gets the position tolerance of this controller.

Returns:

The position tolerance of the controller

Return type:

float

getVelocityTolerance() float

Gets the velocity tolerance of this controller.

Returns:

The velocity tolerance of the controller

Return type:

float

getSetpoint() float

Returns the current setpoint of the PIDController.

Returns:

The current setpoint

Return type:

float

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.

Returns:

True if the error is within the tolerance of the setpoint

Return type:

bool

enableContinuousInput(minimumInput: float, maximumInput: float)

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 (float) – The minimum value expected from the input.

  • maximumInput (float) – The maximum value expected from the input.

disableContinuousInput()

Disables continuous input.

isContinuousInputEnabled() bool

Returns true if continuous input is enabled.

Returns:

True if continuous input is enabled

Return type:

bool

setIntegratorRange(minimumIntegral: float, maximumIntegral: float)

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 (float) – The minimum value of the integrator.

  • maximumIntegral (float) – The maximum value of the integrator.

setTolerance(positionTolerance: float, velocityTolerance: float = math.inf)

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

Parameters:
  • positionTolerance (float) – Position error which is tolerable.

  • velocityTolerance (float) – Velocity error which is tolerable.

getPositionError() float

Returns the difference between the setpoint and the measurement.

Returns:

The position error

Return type:

float

getVelocityError() float

Returns the velocity error.

Returns:

The velocity error

Return type:

float

calculate(measurement: float, setpoint: float, currentTimestamp: phoenix6.units.second) float

Returns the next output of the PID controller.

Parameters:
  • measurement (float) – The current measurement of the process variable

  • setpoint (float) – The new setpoint of the controller

  • currentTimestamp (second) – The current timestamp to use for calculating integral/derivative error

Returns:

The next output

Return type:

float

getLastAppliedOutput() float

Returns the last applied output from this PID controller.

Returns:

The last applied output

Return type:

float

reset()

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