class PIDFController
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants.
pid
- traditional PID coefficients
kV
- feedforward velocity gain
kA
- feedforward acceleration gain
kStatic
- additive feedforward constant
kF
- custom, position-dependent feedforward (e.g., a gravity term for arms)
PIDFController(pid: PIDCoefficients, kV: Double = 0.0, kA: Double = 0.0, kStatic: Double = 0.0, kF: (Double) -> Double = { 0.0 })
PID controller with various feedforward components. kV, kA, and kStatic are designed for DC motor feedforward control (the most common kind of feedforward in FTC). kF provides a custom feedforward term for other plants. |
var lastError: Double
Error computed in the last call to update. |
|
var targetPosition: Double
Target position (that is, the controller setpoint). |
fun reset(): Unit
Reset the controller's integral sum. |
|
fun setInputBounds(min: Double, max: Double): Unit
Sets bound on the input of the controller. The min and max values are considered modularly-equivalent (that is, the input wraps around). |
|
fun setOutputBounds(min: Double, max: Double): Unit
Sets bounds on the output of the controller. |
|
fun update(position: Double, velocity: Double = 0.0, acceleration: Double = 0.0, currentTimestamp: Double = System.nanoTime() / 1e9): Double
Run a single iteration of the controller. |