Class ArmFeedforward
java.lang.Object
com.stuypulse.stuylib.control.Controller
com.stuypulse.stuylib.control.feedforward.ArmFeedforward
A feedforward term to account for gravity for motorized arms.
The motor feedforward used in the context of an arm will not account for gravity that is acting on the arm.
Can be paired with MotorFeedforward or other controllers with .add
-
Constructor Summary
ConstructorDescriptionArmFeedforward
(Number kG) Create arm feedforwardArmFeedforward
(Number kG, IFilter cosine) Create arm feedforward -
Method Summary
Modifier and TypeMethodDescriptionprotected double
calculate
(double setpoint, double measurement) Calculates voltage to hold arm at the setpoint angleMethods inherited from class com.stuypulse.stuylib.control.Controller
add, getError, getMeasurement, getOutput, getSetpoint, isDone, setMeasurementFilter, setOutputFilter, setSetpointFilter, update
-
Constructor Details
-
ArmFeedforward
Create arm feedforward- Parameters:
kG
- term to hold arm vertical against gravity (volts)
-
ArmFeedforward
Create arm feedforward- Parameters:
kG
- term to hold arm vertical against gravity (volts)cosine
- function to calculate cosine of setpoint
-
-
Method Details
-
calculate
protected double calculate(double setpoint, double measurement) Calculates voltage to hold arm at the setpoint angle- Specified by:
calculate
in classController
- Parameters:
setpoint
- setpointmeasurement
- measurement- Returns:
- kG * cos(setpoint)
-