Package edu.wpi.first.wpilibj2.command
Class ProfiledPIDSubsystem
java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
edu.wpi.first.wpilibj2.command.ProfiledPIDSubsystem
public abstract class ProfiledPIDSubsystem extends SubsystemBase
A subsystem that uses a
ProfiledPIDController
to control an output. The controller is run
synchronously from the subsystem's periodic() method.-
Field Summary
Fields Modifier and Type Field Description protected ProfiledPIDController
m_controller
protected boolean
m_enabled
-
Constructor Summary
Constructors Constructor Description ProfiledPIDSubsystem(ProfiledPIDController controller)
Creates a new ProfiledPIDSubsystem.ProfiledPIDSubsystem(ProfiledPIDController controller, double initialPosition)
Creates a new ProfiledPIDSubsystem. -
Method Summary
Modifier and Type Method Description void
disable()
Disables the PID control.void
enable()
Enables the PID control.ProfiledPIDController
getController()
protected abstract double
getMeasurement()
Returns the measurement of the process variable used by the ProfiledPIDController.boolean
isEnabled()
Returns whether the controller is enabled.void
periodic()
This method is called periodically by theCommandScheduler
.void
setGoal(double goal)
Sets the goal state for the subsystem.void
setGoal(TrapezoidProfile.State goal)
Sets the goal state for the subsystem.protected abstract void
useOutput(double output, TrapezoidProfile.State setpoint)
Uses the output from the ProfiledPIDController.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
getCurrentCommand, getDefaultCommand, register, setDefaultCommand, simulationPeriodic
-
Field Details
-
Constructor Details
-
ProfiledPIDSubsystem
Creates a new ProfiledPIDSubsystem.- Parameters:
controller
- the ProfiledPIDController to useinitialPosition
- the initial goal position of the controller
-
ProfiledPIDSubsystem
Creates a new ProfiledPIDSubsystem. Initial goal position is zero.- Parameters:
controller
- the ProfiledPIDController 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
-
setGoal
Sets the goal state for the subsystem.- Parameters:
goal
- The goal state for the subsystem's motion profile.
-
setGoal
Sets the goal state for the subsystem. Goal velocity assumed to be zero.- Parameters:
goal
- The goal position for the subsystem's motion profile.
-
useOutput
Uses the output from the ProfiledPIDController.- Parameters:
output
- the output of the ProfiledPIDControllersetpoint
- the setpoint state of the ProfiledPIDController, for feedforward
-
getMeasurement
Returns the measurement of the process variable used by the ProfiledPIDController.- 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.
-