RIT VEXU Core API
|
#include <feedforward.h>
Public Member Functions | |
Feedforward (double kS, double kV, double kA) | |
double | calculate (double v, double a) const |
double | max_vel (double max_voltage) const |
double | max_acc (double max_voltage) const |
Stores feedforward constants and allows computation of voltage from reference vel/acc.
Feedforward should be used in systsems that require smooth precise movements and have high inertia, such as drivetrains and lifts. It is also useful for flywheels since they're so simple.
The formula used is:
output = kS * sign(v) + kV * v + kA * a
where:
This is best used alongside a PID loop:
output = pid.calculate() + feedforward.calculate(vel, acc)
In this case the feedforward does the heavy lifting and the PID corrects for small errors.
For information about tuning feedforward, I reccommend looking at this post: https://www.chiefdelphi.com/t/paper-frc-drivetrain-characterization/160915 (yes I know it's for FRC but trust me, it's useful)
|
inline |
Constructs a Feedforward with the given parameters.
kS | The static gain. |
kV | The velocity gain. |
kA | The acceleration gain. |
|
inline |
Calculates the output voltage based on the velocity and acceleration commands.
v | The current velocity command. |
a | The current acceleration command. |
|
inline |
Calculates the maximum acceleration that can be achieved with a given maximum voltage.
max_voltage | The maximum voltage that can be applied. |
|
inline |
Calculates the maximum velocity that can be achieved with a given maximum voltage.
max_voltage | The maximum voltage that can be applied. |