Class SpeedLimiter
Defined in File speed_limiter.hpp
Class Documentation
-
class SpeedLimiter
Public Functions
-
SpeedLimiter(bool has_velocity_limits = false, bool has_acceleration_limits = false, bool has_jerk_limits = false, double min_velocity = NAN, double max_velocity = NAN, double min_acceleration = NAN, double max_acceleration = NAN, double min_jerk = NAN, double max_jerk = NAN)
Constructor.
- Parameters:
has_velocity_limits – [in] if true, applies velocity limits
has_acceleration_limits – [in] if true, applies acceleration limits
has_jerk_limits – [in] if true, applies jerk limits
min_velocity – [in] Minimum velocity [m/s], usually <= 0
max_velocity – [in] Maximum velocity [m/s], usually >= 0
min_acceleration – [in] Minimum acceleration [m/s^2], usually <= 0
max_acceleration – [in] Maximum acceleration [m/s^2], usually >= 0
min_jerk – [in] Minimum jerk [m/s^3], usually <= 0
max_jerk – [in] Maximum jerk [m/s^3], usually >= 0
-
double limit(double &v, double v0, double v1, double dt)
Limit the velocity and acceleration.
- Parameters:
v – [inout] Velocity [m/s]
v0 – [in] Previous velocity to v [m/s]
v1 – [in] Previous velocity to v0 [m/s]
dt – [in] Time step [s]
- Returns:
Limiting factor (1.0 if none)
-
double limit_velocity(double &v)
Limit the velocity.
- Parameters:
v – [inout] Velocity [m/s]
- Returns:
Limiting factor (1.0 if none)
-
double limit_acceleration(double &v, double v0, double dt)
Limit the acceleration.
- Parameters:
v – [inout] Velocity [m/s]
v0 – [in] Previous velocity [m/s]
dt – [in] Time step [s]
- Returns:
Limiting factor (1.0 if none)
-
double limit_jerk(double &v, double v0, double v1, double dt)
Limit the jerk.
- Parameters:
v – [inout] Velocity [m/s]
v0 – [in] Previous velocity to v [m/s]
v1 – [in] Previous velocity to v0 [m/s]
dt – [in] Time step [s]
- Returns:
Limiting factor (1.0 if none)
-
SpeedLimiter(bool has_velocity_limits = false, bool has_acceleration_limits = false, bool has_jerk_limits = false, double min_velocity = NAN, double max_velocity = NAN, double min_acceleration = NAN, double max_acceleration = NAN, double min_jerk = NAN, double max_jerk = NAN)