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

#include <arm_feedforward.h>

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

Public Member Functions

 ArmFeedforward (double kS, double kV, double kA, double kG)
 
double calculate (double v, double a, Rotation2d angle) const
 
- Public Member Functions inherited from core::Feedforward
 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

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:

  • kS is the static gain
  • kV is the velocity gain
  • kA is the acceleration gain
  • kG is the gravity gain
  • angle is the current angle of the arm (specifically the CG), for a lift this is always 0
Author
Jack Cammarata
Date
6/27/2025

Constructor & Destructor Documentation

◆ ArmFeedforward()

core::ArmFeedforward::ArmFeedforward ( double kS,
double kV,
double kA,
double kG )
inline

Constructs an ArmFeedforward with the given parameters.

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

Member Function Documentation

◆ calculate()

double core::ArmFeedforward::calculate ( double v,
double a,
Rotation2d angle ) const
inline

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

Parameters
vThe current velocity command.
aThe current acceleration command.
angleThe current angle of the arm.
Returns
The calculated output voltage.

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