|
| SpeedLimiter (bool has_velocity_limits=true, bool has_acceleration_limits=true, bool has_jerk_limits=true, double min_velocity=std::numeric_limits< double >::quiet_NaN(), double max_velocity=std::numeric_limits< double >::quiet_NaN(), double max_deceleration=std::numeric_limits< double >::quiet_NaN(), double max_acceleration=std::numeric_limits< double >::quiet_NaN(), double min_jerk=std::numeric_limits< double >::quiet_NaN(), double max_jerk=std::numeric_limits< double >::quiet_NaN()) |
| Constructor. More...
|
|
| SpeedLimiter (double min_velocity=std::numeric_limits< double >::quiet_NaN(), double max_velocity=std::numeric_limits< double >::quiet_NaN(), double max_acceleration_reverse=std::numeric_limits< double >::quiet_NaN(), double max_acceleration=std::numeric_limits< double >::quiet_NaN(), double max_deceleration=std::numeric_limits< double >::quiet_NaN(), double max_deceleration_reverse=std::numeric_limits< double >::quiet_NaN(), double min_jerk=std::numeric_limits< double >::quiet_NaN(), double max_jerk=std::numeric_limits< double >::quiet_NaN()) |
| Constructor. More...
|
|
double | limit (double &v, double v0, double v1, double dt) |
| Limit the velocity and acceleration. More...
|
|
double | limit_velocity (double &v) |
| Limit the velocity. More...
|
|
double | limit_acceleration (double &v, double v0, double dt) |
| Limit the acceleration. More...
|
|
double | limit_jerk (double &v, double v0, double v1, double dt) |
| Limit the jerk. More...
|
|
◆ SpeedLimiter() [1/2]
diff_drive_controller::SpeedLimiter::SpeedLimiter |
( |
bool |
has_velocity_limits = true , |
|
|
bool |
has_acceleration_limits = true , |
|
|
bool |
has_jerk_limits = true , |
|
|
double |
min_velocity = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
max_velocity = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
max_deceleration = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
max_acceleration = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
min_jerk = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
max_jerk = std::numeric_limits<double>::quiet_NaN() |
|
) |
| |
|
inline |
Constructor.
- Parameters
-
[in] | has_velocity_limits | if true, applies velocity limits |
[in] | has_acceleration_limits | if true, applies acceleration limits |
[in] | has_jerk_limits | if true, applies jerk limits |
[in] | min_velocity | Minimum velocity [m/s], usually <= 0 |
[in] | max_velocity | Maximum velocity [m/s], usually >= 0 |
[in] | max_deceleration | Maximum deceleration [m/s^2], usually <= 0 |
[in] | max_acceleration | Maximum acceleration [m/s^2], usually >= 0 |
[in] | min_jerk | Minimum jerk [m/s^3], usually <= 0 |
[in] | max_jerk | Maximum jerk [m/s^3], usually >= 0 |
◆ SpeedLimiter() [2/2]
diff_drive_controller::SpeedLimiter::SpeedLimiter |
( |
double |
min_velocity = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
max_velocity = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
max_acceleration_reverse = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
max_acceleration = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
max_deceleration = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
max_deceleration_reverse = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
min_jerk = std::numeric_limits<double>::quiet_NaN() , |
|
|
double |
max_jerk = std::numeric_limits<double>::quiet_NaN() |
|
) |
| |
|
inline |
Constructor.
- Parameters
-
[in] | min_velocity | Minimum velocity [m/s], usually <= 0 |
[in] | max_velocity | Maximum velocity [m/s], usually >= 0 |
[in] | max_acceleration_reverse | Maximum acceleration in reverse direction [m/s^2], usually <= 0 |
[in] | max_acceleration | Maximum acceleration [m/s^2], usually >= 0 |
[in] | max_deceleration | Maximum deceleration [m/s^2], usually <= 0 |
[in] | max_deceleration_reverse | Maximum deceleration in reverse direction [m/s^2], usually >= 0 |
[in] | min_jerk | Minimum jerk [m/s^3], usually <= 0 |
[in] | max_jerk | Maximum jerk [m/s^3], usually >= 0 |
◆ limit()
double diff_drive_controller::SpeedLimiter::limit |
( |
double & |
v, |
|
|
double |
v0, |
|
|
double |
v1, |
|
|
double |
dt |
|
) |
| |
|
inline |
Limit the velocity and acceleration.
- Parameters
-
[in,out] | v | Velocity [m/s] |
[in] | v0 | Previous velocity to v [m/s] |
[in] | v1 | Previous velocity to v0 [m/s] |
[in] | dt | Time step [s] |
- Returns
- Limiting factor (1.0 if none)
◆ limit_acceleration()
double diff_drive_controller::SpeedLimiter::limit_acceleration |
( |
double & |
v, |
|
|
double |
v0, |
|
|
double |
dt |
|
) |
| |
|
inline |
Limit the acceleration.
- Parameters
-
[in,out] | v | Velocity [m/s] |
[in] | v0 | Previous velocity [m/s] |
[in] | dt | Time step [s] |
- Returns
- Limiting factor (1.0 if none)
◆ limit_jerk()
double diff_drive_controller::SpeedLimiter::limit_jerk |
( |
double & |
v, |
|
|
double |
v0, |
|
|
double |
v1, |
|
|
double |
dt |
|
) |
| |
|
inline |
◆ limit_velocity()
double diff_drive_controller::SpeedLimiter::limit_velocity |
( |
double & |
v | ) |
|
|
inline |
Limit the velocity.
- Parameters
-
- Returns
- Limiting factor (1.0 if none)
The documentation for this class was generated from the following file:
- ros2_controllers/diff_drive_controller/include/diff_drive_controller/speed_limiter.hpp