PIDSubsystem

class wpilib.command.PIDSubsystem(p, i, d, period=None, f=0.0, name=None)[source]

Bases: wpilib.command.Subsystem

This class is designed to handle the case where there is a Subsystem which uses a single {@link 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.

Instantiates a PIDSubsystem that will use the given p, i and d values. It will use the class name as its name unless otherwise specified. 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
  • period – the time (in seconds) between calculations (optional)
  • f – the feed forward value
  • name – the name (optional)
disable()[source]

Disables the internal PIDController

enable()[source]

Enables the internal PIDController

getPIDController()[source]

Returns the PIDController used by this PIDSubsystem. Use this if you would like to fine tune the pid loop.

Notice that calling setSetpoint() on the controller will not result in the setpoint being trimmed to be in the range defined by setSetpointRange().

Returns:the PIDController used by this PIDSubsystem
getPosition()[source]

Returns the current position

Returns:the current position
getSetpoint()[source]

Returns the setpoint.

Returns:the setpoint
onTarget()[source]

Return True if the error is within the percentage of the total input range, determined by setAbsoluteTolerance or setPercentTolerance. This assumes that the maximum and minimum input were set using setInput.

Returns:True if the error is less than the tolerance
returnPIDInput()[source]

Returns the input for the pid loop.

It returns the input for the pid loop, so if this command was based off of a gyro, then it should return the angle of the gyro

All subclasses of PIDSubsystem must override this method.

This method will be called in a different thread then the Scheduler thread.

Returns:the value the pid loop should use as input
setAbsoluteTolerance(t)[source]

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

Parameters:t – The absolute tolerance (same range as the PIDInput values)
setInputRange(minimumInput, maximumInput)[source]

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, maximumOutput)[source]

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(p)[source]

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

Parameters:p – The percentage tolerance (value of 15.0 == 15 percent)
setSetpoint(setpoint)[source]

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)[source]

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)[source]

Uses the value that the pid loop calculated. The calculated value is the “output” parameter. This method is a good time to set motor values, maybe something along the lines of driveline.tankDrive(output, -output).

All subclasses of PIDSubsystem should override this method.

This method will be called in a different thread then the Scheduler thread.

Parameters:output – the value the pid loop calculated