#include <safety_state_machine.hpp>
Implements stateful behavior for VehicleInterfaceNode Primary function is to ensure vehicle platform does not get conflicting commands
◆ Reports
◆ SafetyStateMachine()
autoware::drivers::vehicle_interface::SafetyStateMachine::SafetyStateMachine |
( |
const StateMachineConfig & |
config | ) |
|
|
explicit |
◆ compute_safe_commands()
Command autoware::drivers::vehicle_interface::SafetyStateMachine::compute_safe_commands |
( |
const Command & |
command | ) |
|
Ensure given commands are consistent and not dangerous. See design document for full list of behaviors.
- Parameters
-
[in] | command | The raw input commands |
- Returns
- Commands which are consistent and safe (within the scope of the vehicle interface)
◆ get_config()
const StateMachineConfig & autoware::drivers::vehicle_interface::SafetyStateMachine::get_config |
( |
| ) |
const |
|
noexcept |
◆ reports()
Get list of warnings state machine saw and adjusted.
◆ timeout_commands()
Command autoware::drivers::vehicle_interface::SafetyStateMachine::timeout_commands |
( |
| ) |
const |
|
noexcept |
Compute safety fallback commands that should be executed on a timeout
- Returns
- The safety fallback command for the current state
◆ update()
void autoware::drivers::vehicle_interface::SafetyStateMachine::update |
( |
const Odometry & |
odom, |
|
|
const StateReport & |
state |
|
) |
| |
Update the state of the state machine
- Parameters
-
[in] | odom | The odometry of the vehicle |
[in] | state | The state of the vehicle |
The documentation for this class was generated from the following files: