Autoware.Auto
autoware::drivers::vehicle_interface::StateMachineConfig Class Reference

Configuration class for SafetyStateMachine. More...

#include <safety_state_machine.hpp>

Public Types

using VelocityT = decltype(Odometry::velocity_mps)
 
using AccelT = decltype(BasicControlCommand::long_accel_mps2)
 
using AccelLimits = Limits< AccelT >
 
using FrontWheelLimits = Limits< decltype(BasicControlCommand::front_wheel_angle_rad)>
 

Public Member Functions

 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)
 
VelocityT gear_shift_velocity_threshold () const noexcept
 
const AccelLimitsaccel_limits () const noexcept
 
const FrontWheelLimitsfront_wheel_limits () const noexcept
 
std::chrono::nanoseconds time_step () const noexcept
 
AccelT timeout_acceleration () const noexcept
 
std::chrono::nanoseconds state_transition_timeout () const noexcept
 
AccelT auto_gear_shift_accel_deadzone () const noexcept
 

Detailed Description

Configuration class for SafetyStateMachine.

Member Typedef Documentation

◆ AccelLimits

◆ AccelT

using autoware::drivers::vehicle_interface::StateMachineConfig::AccelT = decltype(BasicControlCommand::long_accel_mps2)

◆ FrontWheelLimits

using autoware::drivers::vehicle_interface::StateMachineConfig::FrontWheelLimits = Limits<decltype(BasicControlCommand::front_wheel_angle_rad)>

◆ VelocityT

Constructor & Destructor Documentation

◆ 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_thresholdGear 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_limitsMax/min value for command acceleration
[in]front_wheel_limitsMax/min value for commanded wheel angles
[in]time_stepCharacteristic time step of the system: used for computing timeout acceleration commands and when to do autonomous gear shifting. Must be postiive
[in]timeout_accel_mps2Magnitude of acceleration to use to bring the vehicle to a stop when the vehicle interface has timed out. Must be positive
[in]state_transition_timeoutIf 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_mps2Acceleration must be bigger than this magnitude to induce an automatic gear shift. Must be positive.
Exceptions
std::domain_errorIf gear_shift_velocity_threshold is negative
std::domain_errorIf time_step is non-positive
std::domain_errorIf timeout_accel_mps2 is non-positive, or outside of accel_limits
std::domain_errorIf state_transition_timeout is smaller than time_step
std::domain_errorIf auto_gear_shift_accel_deadzone_mps2 is non-positive

Member Function Documentation

◆ accel_limits()

const StateMachineConfig::AccelLimits & autoware::drivers::vehicle_interface::StateMachineConfig::accel_limits ( ) const
noexcept

◆ auto_gear_shift_accel_deadzone()

StateMachineConfig::AccelT autoware::drivers::vehicle_interface::StateMachineConfig::auto_gear_shift_accel_deadzone ( ) const
noexcept

◆ front_wheel_limits()

const StateMachineConfig::FrontWheelLimits & autoware::drivers::vehicle_interface::StateMachineConfig::front_wheel_limits ( ) const
noexcept

◆ gear_shift_velocity_threshold()

StateMachineConfig::VelocityT autoware::drivers::vehicle_interface::StateMachineConfig::gear_shift_velocity_threshold ( ) const
noexcept

◆ 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()

StateMachineConfig::AccelT autoware::drivers::vehicle_interface::StateMachineConfig::timeout_acceleration ( ) const
noexcept

The documentation for this class was generated from the following files: