RIT VEXU Core API
|
#include <arm_feedforward.h>
Public Member Functions | |
ArmFeedforward (double kS, double kV, double kA, double kG) | |
double | calculate (double v, double a, Rotation2d angle) const |
![]() | |
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 |
ArmFeedforward is an extension of the Feedforward class that adds a gravity compensation term for use in arms/lifts. It calculates the output required to hold the mechanism in place against gravity.
The formula used is:
output = kS * sign(v) + kV * v + kA * a + kG * cos(angle)
where:
|
inline |
Constructs an ArmFeedforward with the given parameters.
kS | The static gain. |
kG | The gravity 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. |
angle | The current angle of the arm. |