RIT VEXU Core API
Loading...
Searching...
No Matches
core::Feedforward Class Reference

#include <feedforward.h>

Inheritance diagram for core::Feedforward:
core::ArmFeedforward

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
 

Detailed Description

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:

  • kS is the static gain (voltage required to overcome static friction)
  • kV is the velocity gain (voltage required to maintain a constant velocity)
  • kA is the acceleration gain (voltage required to accelerate at a constant rate)

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)

Author
Ryan McGee, Jack Cammarata
Date
6/13/2022, 6/27/2025

Constructor & Destructor Documentation

◆ Feedforward()

core::Feedforward::Feedforward ( double kS,
double kV,
double kA )
inline

Constructs a Feedforward with the given parameters.

Parameters
kSThe static gain.
kVThe velocity gain.
kAThe acceleration gain.

Member Function Documentation

◆ calculate()

double core::Feedforward::calculate ( double v,
double a ) const
inline

Calculates the output voltage based on the velocity and acceleration commands.

Parameters
vThe current velocity command.
aThe current acceleration command.
Returns
The calculated output voltage.

◆ max_acc()

double core::Feedforward::max_acc ( double max_voltage) const
inline

Calculates the maximum acceleration that can be achieved with a given maximum voltage.

Parameters
max_voltageThe maximum voltage that can be applied.
Returns
The maximum acceleration that can be achieved.

◆ max_vel()

double core::Feedforward::max_vel ( double max_voltage) const
inline

Calculates the maximum velocity that can be achieved with a given maximum voltage.

Parameters
max_voltageThe maximum voltage that can be applied.
Returns
The maximum velocity that can be achieved.

The documentation for this class was generated from the following file: