public 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.
Constructor and Description |
---|
PIDFController(PIDCoefficients pid,
double kV,
double kA,
double kStatic,
kotlin.jvm.functions.Function1<? super java.lang.Double,java.lang.Double> kF)
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.
|
PIDFController(PIDCoefficients pid,
double kV,
double kA,
double kStatic)
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.
|
PIDFController(PIDCoefficients pid,
double kV,
double kA)
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.
|
PIDFController(PIDCoefficients pid,
double kV)
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.
|
PIDFController(PIDCoefficients pid)
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.
|
Modifier and Type | Method and Description |
---|---|
double |
getLastError()
Error computed in the last call to
PIDFController.update . |
double |
getTargetPosition()
Target position (that is, the controller setpoint).
|
void |
reset()
Reset the controller's integral sum.
|
void |
setInputBounds(double min,
double max)
Sets bound on the input of the controller. The min and max values are considered modularly-equivalent (that is,
the input wraps around).
|
void |
setOutputBounds(double min,
double max)
Sets bounds on the output of the controller.
|
void |
setTargetPosition(double p)
Target position (that is, the controller setpoint).
|
double |
update(double position,
double velocity,
double acceleration,
double currentTimestamp)
Run a single iteration of the controller.
|
double |
update(double position,
double velocity,
double acceleration)
Run a single iteration of the controller.
|
double |
update(double position,
double velocity)
Run a single iteration of the controller.
|
double |
update(double position)
Run a single iteration of the controller.
|
public PIDFController(PIDCoefficients pid, double kV, double kA, double kStatic, kotlin.jvm.functions.Function1<? super java.lang.Double,java.lang.Double> kF)
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 coefficientskV
- feedforward velocity gainkA
- feedforward acceleration gainkStatic
- additive feedforward constantkF
- custom, position-dependent feedforward (e.g., a gravity term for arms)pid
- traditional PID coefficientskV
- feedforward velocity gainkA
- feedforward acceleration gainkStatic
- additive feedforward constantkF
- custom, position-dependent feedforward (e.g., a gravity term for arms)public PIDFController(PIDCoefficients pid, double kV, double kA, double kStatic)
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 coefficientskV
- feedforward velocity gainkA
- feedforward acceleration gainkStatic
- additive feedforward constantpid
- traditional PID coefficientskV
- feedforward velocity gainkA
- feedforward acceleration gainkStatic
- additive feedforward constantpublic PIDFController(PIDCoefficients pid, double kV, double kA)
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 coefficientskV
- feedforward velocity gainkA
- feedforward acceleration gainpid
- traditional PID coefficientskV
- feedforward velocity gainkA
- feedforward acceleration gainpublic PIDFController(PIDCoefficients pid, double kV)
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 coefficientskV
- feedforward velocity gainpid
- traditional PID coefficientskV
- feedforward velocity gainpublic PIDFController(PIDCoefficients pid)
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 coefficientspid
- traditional PID coefficientspublic double getTargetPosition()
Target position (that is, the controller setpoint).
public void setTargetPosition(double p)
Target position (that is, the controller setpoint).
public double getLastError()
Error computed in the last call to PIDFController.update
.
PIDFController.update
public void setInputBounds(double min, double max)
Sets bound on the input of the controller. The min and max values are considered modularly-equivalent (that is, the input wraps around).
min
- minimum inputmax
- maximum inputpublic void setOutputBounds(double min, double max)
Sets bounds on the output of the controller.
min
- minimum outputmax
- maximum outputpublic double update(double position, double velocity, double acceleration, double currentTimestamp)
Run a single iteration of the controller.
position
- current measured position (feedback)velocity
- feedforward velocityacceleration
- feedforward accelerationcurrentTimestamp
- timestamp for the above parameters (intendend for simulation)public double update(double position, double velocity, double acceleration)
Run a single iteration of the controller.
position
- current measured position (feedback)velocity
- feedforward velocityacceleration
- feedforward accelerationpublic double update(double position, double velocity)
Run a single iteration of the controller.
position
- current measured position (feedback)velocity
- feedforward velocitypublic double update(double position)
Run a single iteration of the controller.
position
- current measured position (feedback)public void reset()
Reset the controller's integral sum.