|
Autoware.Auto
|
|
Extreme values for state/control variables. More...
#include <config.hpp>
Classes | |
| class | Extremum |
| Class representing min and max values for a variable. More... | |
Public Member Functions | |
| LimitsConfig (Extremum longitudinal_velocity_mps, Extremum lateral_velocity_mps, Extremum acceleration_mps2, Extremum yaw_rate_rps, Extremum jerk_mps3, Extremum steer_angle_rad, Extremum steer_angle_rate_rps) | |
| Extremum | longitudinal_velocity () const noexcept |
| Extremum | lateral_velocity () const noexcept |
| Extremum | acceleration () const noexcept |
| Extremum | jerk () const noexcept |
| Extremum | yaw_rate () const noexcept |
| Extremum | steer_angle () const noexcept |
| Extremum | steer_angle_rate () const noexcept |
Extreme values for state/control variables.
| motion::motion_common::LimitsConfig::LimitsConfig | ( | Extremum | longitudinal_velocity_mps, |
| Extremum | lateral_velocity_mps, | ||
| Extremum | acceleration_mps2, | ||
| Extremum | yaw_rate_rps, | ||
| Extremum | jerk_mps3, | ||
| Extremum | steer_angle_rad, | ||
| Extremum | steer_angle_rate_rps | ||
| ) |
|
noexcept |
|
noexcept |
|
noexcept |
|
noexcept |
|
noexcept |
|
noexcept |
|
noexcept |