Package edu.wpi.first.wpilibj2.command
Class PIDSubsystem
java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
edu.wpi.first.wpilibj2.command.PIDSubsystem
public abstract class PIDSubsystem extends SubsystemBase
A subsystem that uses a
PIDController
to control an output. The controller is run
synchronously from the subsystem's periodic() method.
This class is provided by the NewCommands VendorDep
-
Field Summary
Fields Modifier and Type Field Description protected PIDController
m_controller
PID controller.protected boolean
m_enabled
Whether PID controller output is enabled. -
Constructor Summary
Constructors Constructor Description PIDSubsystem(PIDController controller)
Creates a new PIDSubsystem.PIDSubsystem(PIDController controller, double initialPosition)
Creates a new PIDSubsystem. -
Method Summary
Modifier and Type Method Description void
disable()
Disables the PID control.void
enable()
Enables the PID control.PIDController
getController()
Returns the PIDController.protected abstract double
getMeasurement()
Returns the measurement of the process variable used by the PIDController.double
getSetpoint()
Returns the current setpoint of the subsystem.boolean
isEnabled()
Returns whether the controller is enabled.void
periodic()
This method is called periodically by theCommandScheduler
.void
setSetpoint(double setpoint)
Sets the setpoint for the subsystem.protected abstract void
useOutput(double output, double setpoint)
Uses the output from the PIDController.Methods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase
addChild, getName, getSubsystem, initSendable, setName, setSubsystem
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
Methods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem
defer, getCurrentCommand, getDefaultCommand, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, simulationPeriodic, startEnd
-
Field Details
-
m_controller
PID controller. -
m_enabled
Whether PID controller output is enabled.
-
-
Constructor Details
-
PIDSubsystem
Creates a new PIDSubsystem.- Parameters:
controller
- the PIDController to useinitialPosition
- the initial setpoint of the subsystem
-
PIDSubsystem
Creates a new PIDSubsystem. Initial setpoint is zero.- Parameters:
controller
- the PIDController to use
-
-
Method Details
-
periodic
Description copied from interface:Subsystem
This method is called periodically by theCommandScheduler
. Useful for updating subsystem-specific state that you don't want to offload to aCommand
. Teams should try to be consistent within their own codebases about which responsibilities will be handled by Commands, and which will be handled here. -
getController
Returns the PIDController.- Returns:
- The controller.
-
setSetpoint
Sets the setpoint for the subsystem.- Parameters:
setpoint
- the setpoint for the subsystem
-
getSetpoint
Returns the current setpoint of the subsystem.- Returns:
- The current setpoint
-
useOutput
Uses the output from the PIDController.- Parameters:
output
- the output of the PIDControllersetpoint
- the setpoint of the PIDController (for feedforward)
-
getMeasurement
Returns the measurement of the process variable used by the PIDController.- Returns:
- the measurement of the process variable
-
enable
Enables the PID control. Resets the controller. -
disable
Disables the PID control. Sets output to zero. -
isEnabled
Returns whether the controller is enabled.- Returns:
- Whether the controller is enabled.
-