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

#include <pidff.h>

Public Member Functions

 PIDFF (double kP, double kI, double kD, double kS, double kV, double kA, double kG, double tolerance, double dt=0.01)
 
void set_gains (double kP, double kI, double kD, double kS, double kV, double kA, double kG)
 
void set_pid (double kP, double kI, double kD)
 
void set_ff (double kS, double kV, double kA, double kG)
 
void set_setpoint (double setpoint)
 
double setpoint () const
 
void set_output_limits (double minimum_output, double maximum_output)
 
double calculate (double measurement, Rotation2d angle=Rotation2d())
 
double calculate (double setpoint, double measurement, Rotation2d angle=Rotation2d())
 
double calculate_with_ff (double measurement, double v, double a, Rotation2d angle=Rotation2d())
 
double calculate_with_ff (double setpoint, double measurement, double v, double a, Rotation2d angle=Rotation2d())
 

Detailed Description

Creates a PIDFF controller that combines PID and Feedforward control.

This controller uses both feedback (PID) and feedforward control to improve tracking performance. The feedforward component handles the known dynamics of the system, while the PID component handles errors and disturbances.

output = pid_output + feedforward_output

Author
Jack Cammarata
Date
6/27/2025

Constructor & Destructor Documentation

◆ PIDFF()

core::PIDFF::PIDFF ( double kP,
double kI,
double kD,
double kS,
double kV,
double kA,
double kG,
double tolerance,
double dt = 0.01 )
inline

Constructs a PIDFF controller with the given parameters.

Parameters
kPThe proportional gain.
kIThe integral gain.
kDThe derivative gain.
kSThe static gain.
kVThe velocity gain.
kAThe acceleration gain.
kGThe gravity compensation gain.
toleranceThe tolerance value for determining if at setpoint.
dtThe time step in seconds.

Member Function Documentation

◆ calculate() [1/2]

double core::PIDFF::calculate ( double measurement,
Rotation2d angle = Rotation2d() )
inline

Calculates the PIDFF output based on the current measurement. Uses only kS and kG from feedforward (no velocity or acceleration terms).

Parameters
measurementThe current measurement value.
angleThe current angle (for gravity compensation).
Returns
The calculated PIDFF output.

◆ calculate() [2/2]

double core::PIDFF::calculate ( double setpoint,
double measurement,
Rotation2d angle = Rotation2d() )
inline

Calculates the PIDFF output based on the current measurement and a new setpoint. Uses only kS and kG from feedforward (no velocity or acceleration terms).

Parameters
setpointThe desired setpoint value.
measurementThe current measurement value.
angleThe current angle (for gravity compensation).
Returns
The calculated PIDFF output.

◆ calculate_with_ff() [1/2]

double core::PIDFF::calculate_with_ff ( double measurement,
double v,
double a,
Rotation2d angle = Rotation2d() )
inline

Calculates the PIDFF output based on the current measurement and velocity/acceleration commands.

Parameters
measurementThe current measurement value.
vThe velocity command.
aThe acceleration command.
angleThe current angle (for gravity compensation).
Returns
The calculated PIDFF output.

◆ calculate_with_ff() [2/2]

double core::PIDFF::calculate_with_ff ( double setpoint,
double measurement,
double v,
double a,
Rotation2d angle = Rotation2d() )
inline

Calculates the PIDFF output based on a new setpoint, measurement, and velocity/acceleration commands.

Parameters
setpointThe new setpoint value.
measurementThe current measurement value.
vThe velocity command.
aThe acceleration command.
angleThe current angle (for gravity compensation).
Returns
The calculated PIDFF output.

◆ set_ff()

void core::PIDFF::set_ff ( double kS,
double kV,
double kA,
double kG )
inline

Sets the Feedforward gains.

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

◆ set_gains()

void core::PIDFF::set_gains ( double kP,
double kI,
double kD,
double kS,
double kV,
double kA,
double kG )
inline

Sets both the PID and Feedforward gains.

Parameters
kPThe proportional gain.
kIThe integral gain.
kDThe derivative gain.
kSThe static gain.
kVThe velocity gain.
kAThe acceleration gain.
kGThe gravity compensation gain.

◆ set_output_limits()

void core::PIDFF::set_output_limits ( double minimum_output,
double maximum_output )
inline

Sets the output limits.

Parameters
minimum_outputThe minimum output value.
maximum_outputThe maximum output value.

◆ set_pid()

void core::PIDFF::set_pid ( double kP,
double kI,
double kD )
inline

Sets the PID gains.

Parameters
kPThe proportional gain.
kIThe integral gain.
kDThe derivative gain.

◆ set_setpoint()

void core::PIDFF::set_setpoint ( double setpoint)
inline

Sets the setpoint.

Parameters
setpointThe setpoint value.

◆ setpoint()

double core::PIDFF::setpoint ( ) const
inline

Returns the current setpoint.

Returns
The setpoint value.

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