Trajectories¶
-
struct ProfileSetpoint¶
a setpoint during a given time
Public Functions
-
inline ProfileSetpoint direct(bool invert) const¶
Calculate the angle from the current position of the robot to a point.
- Parameters:
invert – reverse
- Returns:
the setpoint at the given point
-
inline ProfileSetpoint direct(bool invert) const¶
-
enum class dlib::TrapezoidProfileStage¶
a class of trapezoid profile stages
Values:
-
enumerator Accelerating¶
-
enumerator Coasting¶
-
enumerator Decelerating¶
-
enumerator Done¶
-
enumerator Accelerating¶
-
class TrapezoidProfile¶
Calculate the angle from the current position of the robot to a point class for trapezoid profile methods.
Public Functions
-
inline TrapezoidProfileStage stage(double elapsed_time) const¶
Find the state of the robot during a motion profile movement.
- Parameters:
elapsed_time – the elapsed time of the movement
- Returns:
current state of the motion profile
-
inline ProfileSetpoint calculate(double elapsed_time) const¶
Find the state of the robot during a motion profile movement.
- Parameters:
elapsed_time – the elapsed time of the movement
- Returns:
current state of the motion profile
Public Static Functions
- static inline TrapezoidProfile from_constraints(
- double total_distance,
- double max_velocity,
- double max_acceleration,
create a trapezoid profile based on constraints
- Parameters:
total_distance –
max_velocity –
max_acceleration –
- Returns:
-
inline TrapezoidProfileStage stage(double elapsed_time) const¶