RIT VEXU Core API
|
#include <pidff.h>
Public Member Functions | |
PIDFF (double kP, double kI, double kD, double kS, double kV, double kA, double kG, double tolerance, double dt=0.01) | |
void | set_gains (double kP, double kI, double kD, double kS, double kV, double kA, double kG) |
void | set_pid (double kP, double kI, double kD) |
void | set_ff (double kS, double kV, double kA, double kG) |
void | set_setpoint (double setpoint) |
double | setpoint () const |
void | set_output_limits (double minimum_output, double maximum_output) |
double | calculate (double measurement, Rotation2d angle=Rotation2d()) |
double | calculate (double setpoint, double measurement, Rotation2d angle=Rotation2d()) |
double | calculate_with_ff (double measurement, double v, double a, Rotation2d angle=Rotation2d()) |
double | calculate_with_ff (double setpoint, double measurement, double v, double a, Rotation2d angle=Rotation2d()) |
Creates a PIDFF controller that combines PID and Feedforward control.
This controller uses both feedback (PID) and feedforward control to improve tracking performance. The feedforward component handles the known dynamics of the system, while the PID component handles errors and disturbances.
output = pid_output + feedforward_output
|
inline |
Constructs a PIDFF controller with the given parameters.
kP | The proportional gain. |
kI | The integral gain. |
kD | The derivative gain. |
kS | The static gain. |
kV | The velocity gain. |
kA | The acceleration gain. |
kG | The gravity compensation gain. |
tolerance | The tolerance value for determining if at setpoint. |
dt | The time step in seconds. |
|
inline |
|
inline |
Calculates the PIDFF output based on the current measurement and a new setpoint. Uses only kS and kG from feedforward (no velocity or acceleration terms).
setpoint | The desired setpoint value. |
measurement | The current measurement value. |
angle | The current angle (for gravity compensation). |
|
inline |
|
inline |
Calculates the PIDFF output based on a new setpoint, measurement, and velocity/acceleration commands.
setpoint | The new setpoint value. |
measurement | The current measurement value. |
v | The velocity command. |
a | The acceleration command. |
angle | The current angle (for gravity compensation). |
|
inline |
Sets the Feedforward gains.
kS | The static gain. |
kV | The velocity gain. |
kA | The acceleration gain. |
kG | The gravity compensation gain. |
|
inline |
Sets both the PID and Feedforward gains.
kP | The proportional gain. |
kI | The integral gain. |
kD | The derivative gain. |
kS | The static gain. |
kV | The velocity gain. |
kA | The acceleration gain. |
kG | The gravity compensation gain. |
|
inline |
Sets the output limits.
minimum_output | The minimum output value. |
maximum_output | The maximum output value. |
|
inline |
Sets the PID gains.
kP | The proportional gain. |
kI | The integral gain. |
kD | The derivative gain. |
|
inline |
Sets the setpoint.
setpoint | The setpoint value. |
|
inline |
Returns the current setpoint.