RIT VEXU Core API
Loading...
Searching...
No Matches
TrapezoidProfile Class Reference

#include <trapezoid_profile.h>

Public Member Functions

 TrapezoidProfile (const double &x_initial, const double &x_target, const double &v_max, const double &accel, const double &decel)
 
motion_t calculate (double t)
 
double total_time ()
 
 TrapezoidProfile (const double &x_initial, const double &x_target, const double &v_max, const double &accel, const double &decel)
 
motion_t calculate (double t)
 
double total_time ()
 

Detailed Description

Class representing a trapezoidal motion profile. This consists of either two or three stages. First, an acceleration stage where the velocity increases to a maximum. Then a cruise stage where the velocity is constant, then a deceleration stage where the velocity decreases to zero.

This implementation allows for different acceleration and deceleration rates.

This is best used with LQR, as it tracks both velocity and position at the same time, however it can also be used with PID and feedforward.

Author
Jack Cammarata
Date
3/28/2025

Class representing a trapezoidal motion profile. This consists of either two or three stages. First, an acceleration stage where the velocity increases to a maximum. Then a cruise stage where the velocity is constant, then a deceleration stage where the velocity decreases to zero.

This implementation allows for different acceleration and deceleration rates.

This is best used with LQR, since it allows full state feedback, but it can also be used with PID and Feedforward.

Author
Jack Cammarata
Date
3/28/2025

Constructor & Destructor Documentation

◆ TrapezoidProfile() [1/2]

TrapezoidProfile::TrapezoidProfile ( const double & x_initial,
const double & x_target,
const double & v_max,
const double & accel,
const double & decel )

Constructs a TrapezoidProfile.

Parameters
x_initialThe initial position.
x_targetThe target position.
v_maxThe maximum velocity.
accelThe acceleration.
decelThe deceleration.

◆ TrapezoidProfile() [2/2]

TrapezoidProfile::TrapezoidProfile ( const double & x_initial,
const double & x_target,
const double & v_max,
const double & accel,
const double & decel )
inline

Constructs a TrapezoidProfile.

Parameters
x_initialThe initial position.
x_targetThe target position.
v_maxThe maximum velocity.
accelThe acceleration.
decelThe deceleration.

Member Function Documentation

◆ calculate() [1/2]

motion_t TrapezoidProfile::calculate ( double t)

Calculate the state along the motion profile at some given time.

Parameters
tThe time in seconds.
Returns
the state.

Calculate the state along the motion profile after some given time.

Parameters
tThe time in seconds.
Returns
the state.

◆ calculate() [2/2]

motion_t TrapezoidProfile::calculate ( double t)
inline

Calculate the state along the motion profile at some given time.

Parameters
tThe time in seconds.
Returns
the state.

◆ total_time() [1/2]

double TrapezoidProfile::total_time ( )

Returns the total time that the motion profile takes to complete.

Returns
the total time that the motion profile takes to complete.

◆ total_time() [2/2]

double TrapezoidProfile::total_time ( )
inline

Returns the total time that the motion profile takes to complete.

Returns
the total time that the motion profile takes to complete.

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