RIT VEXU Core API
|
#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 () |
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.
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.
TrapezoidProfile::TrapezoidProfile | ( | const double & | x_initial, |
const double & | x_target, | ||
const double & | v_max, | ||
const double & | accel, | ||
const double & | decel ) |
Constructs a TrapezoidProfile.
x_initial | The initial position. |
x_target | The target position. |
v_max | The maximum velocity. |
accel | The acceleration. |
decel | The deceleration. |
|
inline |
Constructs a TrapezoidProfile.
x_initial | The initial position. |
x_target | The target position. |
v_max | The maximum velocity. |
accel | The acceleration. |
decel | The deceleration. |
motion_t TrapezoidProfile::calculate | ( | double | t | ) |
Calculate the state along the motion profile at some given time.
t | The time in seconds. |
Calculate the state along the motion profile after some given time.
t | The time in seconds. |
|
inline |
Calculate the state along the motion profile at some given time.
t | The time in seconds. |
double TrapezoidProfile::total_time | ( | ) |
Returns the total time that the motion profile takes to complete.
|
inline |
Returns the total time that the motion profile takes to complete.