Configuration class for SafetyStateMachine.
More...
#include <safety_state_machine.hpp>
Configuration class for SafetyStateMachine.
◆ AccelLimits
◆ AccelT
◆ FrontWheelLimits
◆ VelocityT
◆ StateMachineConfig()
autoware::drivers::vehicle_interface::StateMachineConfig::StateMachineConfig |
( |
const VelocityT |
gear_shift_velocity_threshold, |
|
|
const AccelLimits & |
accel_limits, |
|
|
const FrontWheelLimits & |
front_wheel_limits, |
|
|
const std::chrono::nanoseconds |
time_step, |
|
|
const AccelT |
timeout_accel_mps2, |
|
|
const std::chrono::nanoseconds |
state_transition_timeout, |
|
|
const AccelT |
auto_gear_shift_accel_deadzone_mps2 |
|
) |
| |
Constructor
- Parameters
-
[in] | gear_shift_velocity_threshold | Gear shifts between directions (i.e. park->drive, low->reverse are allowed only if the magnitude of velocity is below this threshold. Must be positive |
[in] | accel_limits | Max/min value for command acceleration |
[in] | front_wheel_limits | Max/min value for commanded wheel angles |
[in] | time_step | Characteristic time step of the system: used for computing timeout acceleration commands and when to do autonomous gear shifting. Must be postiive |
[in] | timeout_accel_mps2 | Magnitude of acceleration to use to bring the vehicle to a stop when the vehicle interface has timed out. Must be positive |
[in] | state_transition_timeout | If a state component has not changed within this period, then a warning is raised. Must be positive and bigger than time_step. |
[in] | auto_gear_shift_accel_deadzone_mps2 | Acceleration must be bigger than this magnitude to induce an automatic gear shift. Must be positive. |
- Exceptions
-
std::domain_error | If gear_shift_velocity_threshold is negative |
std::domain_error | If time_step is non-positive |
std::domain_error | If timeout_accel_mps2 is non-positive, or outside of accel_limits |
std::domain_error | If state_transition_timeout is smaller than time_step |
std::domain_error | If auto_gear_shift_accel_deadzone_mps2 is non-positive |
◆ accel_limits()
◆ auto_gear_shift_accel_deadzone()
◆ front_wheel_limits()
◆ gear_shift_velocity_threshold()
◆ state_transition_timeout()
std::chrono::nanoseconds autoware::drivers::vehicle_interface::StateMachineConfig::state_transition_timeout |
( |
| ) |
const |
|
noexcept |
◆ time_step()
std::chrono::nanoseconds autoware::drivers::vehicle_interface::StateMachineConfig::time_step |
( |
| ) |
const |
|
noexcept |
◆ timeout_acceleration()
The documentation for this class was generated from the following files: