Class AnglePIDController
java.lang.Object
com.stuypulse.stuylib.control.angle.AngleController
com.stuypulse.stuylib.control.angle.feedback.AnglePIDController
This PID controller is built by extending the AngleController class. It has a dynamic rate, so it
can detect how much time has passed between each update. It is made to be easy to use and simple
to understand while still being accurate.
The angle PID controller class is ALWAYS in units of *RADIANS*
-
Constructor Summary
ConstructorDescriptionCreates a blank PIDController that doesn't moveAnglePIDController
(Number p, Number i, Number d) -
Method Summary
Modifier and TypeMethodDescriptionprotected double
Calculates the output of the controller given a setpoint and measurement.double
getD()
double
getI()
double
getP()
void
reset()
Resets the integrator in the PIDController.setDerivativeFilter
(IFilter... derivativeFilter) Add a filter to the error velocity / derivative of the PID controller.setIntegratorFilter
(Number range, Number limit) Add constraints to the integral of the PID ControllersetPID
(AnglePIDController pidValues) Methods inherited from class com.stuypulse.stuylib.control.angle.AngleController
add, getError, getMeasurement, getOutput, getSetpoint, isDoneDegrees, isDoneRadians, setMeasurementFilter, setOutputFilter, setSetpointFilter, update
-
Constructor Details
-
AnglePIDController
- Parameters:
p
- The Proportional Multiplieri
- The Integral Multiplierd
- The Derivative Multiplier
-
AnglePIDController
public AnglePIDController()Creates a blank PIDController that doesn't move
-
-
Method Details
-
reset
public void reset()Resets the integrator in the PIDController. This automatically gets called if the gap between update() commands is too large -
calculate
Description copied from class:AngleController
Calculates the output of the controller given a setpoint and measurement.- Specified by:
calculate
in classAngleController
- Parameters:
setpoint
- setpointmeasurement
- measurement- Returns:
- calculated output
-
getP
public double getP()- Returns:
- the P value being used by the PID controller.
-
getI
public double getI()- Returns:
- the P value being used by the PID controller.
-
getD
public double getD()- Returns:
- the P value being used by the PID controller.
-
setP
- Parameters:
p
- new p value used by the PID controller.- Returns:
- reference to PIDController (so you can chain the commands together)
-
setI
- Parameters:
i
- new i value used by the PID controller.- Returns:
- reference to PIDController (so you can chain the commands together)
-
setD
- Parameters:
d
- new d value used by the PID controller.- Returns:
- reference to PIDController (so you can chain the commands together)
-
setPID
- Parameters:
p
- new p value used by the PID controller.i
- new i value used by the PID controller.d
- new d value used by the PID controller.- Returns:
- reference to PIDController (so you can chain the commands together)
-
setPID
- Parameters:
pidValues
- PIDController that stores the PID values- Returns:
- reference to PIDController (so you can chain the commands together)
-
setIntegratorFilter
Add constraints to the integral of the PID Controller- Parameters:
range
- the range of error in which the integral is allowed to accumulate (0 will disable)limit
- the max / min the integral is allowed to accumulate to (0 will disables)- Returns:
- reference to PIDController (so you can chain the commands together)
-
setDerivativeFilter
Add a filter to the error velocity / derivative of the PID controller.- Parameters:
derivativeFilter
- the filter to apply to derivative- Returns:
- reference to PIDController (so you can chain the commands together)
-