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

#include <trapezoid_profile.h>

Public Member Functions

 TrapezoidProfile (double max_v, double accel)
 Construct a new Trapezoid Profile object.
 
motion_t calculate (double time_s)
 Run the trapezoidal profile based on the time that's ellapsed.
 
void set_endpts (double start, double end)
 
void set_accel (double accel)
 
void set_max_v (double max_v)
 
double get_movement_time ()
 

Detailed Description

Trapezoid Profile

This is a motion profile defined by an acceleration, maximum velocity, start point and end point. Using this information, a parametric function is generated, with a period of acceleration, constant velocity, and deceleration. The velocity graph looks like a trapezoid, giving it it's name.

If the maximum velocity is set high enough, this will become a S-curve profile, with only acceleration and deceleration.

This class is designed for use in properly modelling the motion of the robots to create a feedfoward and target for PID. Acceleration and Maximum velocity should be measured on the robot and tuned down slightly to account for battery drop.

Here are the equations graphed for ease of understanding: https://www.desmos.com/calculator/rkm3ivu1yk

Author
Ryan McGee
Date
7/12/2022

Constructor & Destructor Documentation

◆ TrapezoidProfile()

TrapezoidProfile::TrapezoidProfile ( double max_v,
double accel )

Construct a new Trapezoid Profile object.

Parameters
max_vMaximum velocity the robot can run at
accelMaximum acceleration of the robot

Member Function Documentation

◆ calculate()

motion_t TrapezoidProfile::calculate ( double time_s)

Run the trapezoidal profile based on the time that's ellapsed.

Parameters
time_sTime since start of movement
Returns
motion_t Position, velocity and acceleration

◆ get_movement_time()

double TrapezoidProfile::get_movement_time ( )

uses the kinematic equations to and specified accel and max_v to figure out how long moving along the profile would take

Returns
the time the path will take to travel

◆ set_accel()

void TrapezoidProfile::set_accel ( double accel)

set_accel sets the acceleration this profile will use (the left and right legs of the trapezoid)

Parameters
accelthe acceleration amount to use

◆ set_endpts()

void TrapezoidProfile::set_endpts ( double start,
double end )

set_endpts defines a start and end position

Parameters
startthe starting position of the path
endthe ending position of the path

◆ set_max_v()

void TrapezoidProfile::set_max_v ( double max_v)

sets the maximum velocity for the profile (the height of the top of the trapezoid)

Parameters
max_vthe maximum velocity the robot can travel at

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