RIT VEXU Core API
Loading...
Searching...
No Matches
trapezoid_profile.h
1#pragma once
2
6typedef struct {
7 double pos;
8 double vel;
9 double accel;
10
11} motion_t;
12
35public:
42 TrapezoidProfile(double max_v, double accel);
43
50 motion_t calculate(double time_s);
51
57 void set_endpts(double start, double end);
58
63 void set_accel(double accel);
64
70 void set_max_v(double max_v);
71
77 double get_movement_time();
78
79private:
80 double start, end;
81 double max_v;
82 double accel;
83 double time;
84};
Definition trapezoid_profile.h:34
motion_t calculate(double time_s)
Run the trapezoidal profile based on the time that's ellapsed.
Definition trapezoid_profile.cpp:26
void set_endpts(double start, double end)
Definition trapezoid_profile.cpp:11
void set_accel(double accel)
Definition trapezoid_profile.cpp:9
void set_max_v(double max_v)
Definition trapezoid_profile.cpp:7
double get_movement_time()
Definition trapezoid_profile.cpp:96
TrapezoidProfile(double max_v, double accel)
Construct a new Trapezoid Profile object.
Definition trapezoid_profile.cpp:5
Definition trapezoid_profile.h:6
double vel
1d velocity at this point in time
Definition trapezoid_profile.h:8
double accel
1d acceleration at this point in time
Definition trapezoid_profile.h:9
double pos
1d position at this point in time
Definition trapezoid_profile.h:7