PIDSubsystem

class commands1.PIDSubsystem(*args, **kwargs)

Bases: commands1._impl._commands_v1.command.Subsystem, commands1._impl._commands_v1.command.PIDOutput, commands1._impl._commands_v1.command.PIDSource

This class is designed to handle the case where there is a Subsystem which uses a single PIDController almost constantly (for instance, an elevator which attempts to stay at a constant height).

It provides some convenience methods to run an internal PIDController. It also allows access to the internal PIDController in order to give total control to the programmer.

This class is provided by the OldCommands VendorDep

Overloaded function.

  1. __init__(self: commands1._impl._commands_v1.command.PIDSubsystem, name: str, p: float, i: float, d: float) -> None

Instantiates a PIDSubsystem that will use the given P, I, and D values.

Parameters
  • name – the name

  • p – the proportional value

  • i – the integral value

  • d – the derivative value

  1. __init__(self: commands1._impl._commands_v1.command.PIDSubsystem, name: str, p: float, i: float, d: float, f: float) -> None

Instantiates a PIDSubsystem that will use the given P, I, D, and F values.

Parameters
  • name – the name

  • p – the proportional value

  • i – the integral value

  • d – the derivative value

  • f – the feedforward value

  1. __init__(self: commands1._impl._commands_v1.command.PIDSubsystem, name: str, p: float, i: float, d: float, f: float, period: float) -> None

Instantiates a PIDSubsystem that will use the given P, I, D, and F values.

It will also space the time between PID loop calculations to be equal to the given period.

Parameters
  • name – the name

  • p – the proportional value

  • i – the integral value

  • d – the derivative value

  • f – the feedfoward value

  • period – the time (in seconds) between calculations

  1. __init__(self: commands1._impl._commands_v1.command.PIDSubsystem, p: float, i: float, d: float) -> None

Instantiates a PIDSubsystem that will use the given P, I, and D values.

It will use the class name as its name.

Parameters
  • p – the proportional value

  • i – the integral value

  • d – the derivative value

  1. __init__(self: commands1._impl._commands_v1.command.PIDSubsystem, p: float, i: float, d: float, f: float) -> None

Instantiates a PIDSubsystem that will use the given P, I, D, and F values.

It will use the class name as its name.

Parameters
  • p – the proportional value

  • i – the integral value

  • d – the derivative value

  • f – the feedforward value

  1. __init__(self: commands1._impl._commands_v1.command.PIDSubsystem, p: float, i: float, d: float, f: float, period: float) -> None

Instantiates a PIDSubsystem that will use the given P, I, D, and F values.

It will use the class name as its name. It will also space the time between PID loop calculations to be equal to the given period.

Parameters
  • p – the proportional value

  • i – the integral value

  • d – the derivative value

  • f – the feedforward value

  • period – the time (in seconds) between calculations

PIDGet() float
PIDWrite(output: float) None
disable() None

Disables the internal PIDController.

enable() None

Enables the internal PIDController.

getPIDController() None

Returns the PIDController used by this PIDSubsystem.

Use this if you would like to fine tune the PID loop.

Returns

The PIDController used by this PIDSubsystem

getPosition() float

Returns the current position.

Returns

the current position

getRate() float

Returns the current rate.

Returns

the current rate

getSetpoint() float

Return the current setpoint.

Returns

The current setpoint

onTarget() bool

Return true if the error is within the percentage of the total input range, determined by SetTolerance().

This asssumes that the maximum and minimum input were set using SetInput(). Use OnTarget() in the IsFinished() method of commands that use this subsystem.

Currently this just reports on target as the actual value passes through the setpoint. Ideally it should be based on being within the tolerance for some period of time.

Returns

True if the error is within the percentage tolerance of the input range

returnPIDInput() float
setAbsoluteTolerance(absValue: float) None

Set the absolute error which is considered tolerable for use with OnTarget.

Parameters

absValue – absolute error which is tolerable

setInputRange(minimumInput: float, maximumInput: float) None

Sets the maximum and minimum values expected from the input.

Parameters
  • minimumInput – the minimum value expected from the input

  • maximumInput – the maximum value expected from the output

setOutputRange(minimumOutput: float, maximumOutput: float) None

Sets the maximum and minimum values to write.

Parameters
  • minimumOutput – the minimum value to write to the output

  • maximumOutput – the maximum value to write to the output

setPercentTolerance(percent: float) None

Set the percentage error which is considered tolerable for use with OnTarget().

Parameters

percent – percentage error which is tolerable

setSetpoint(setpoint: float) None

Sets the setpoint to the given value.

If SetRange() was called, then the given setpoint will be trimmed to fit within the range.

Parameters

setpoint – the new setpoint

setSetpointRelative(deltaSetpoint: float) None

Adds the given value to the setpoint.

If SetRange() was used, then the bounds will still be honored by this method.

Parameters

deltaSetpoint – the change in the setpoint

usePIDOutput(output: float) None