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

Class for maintaining the DBW state. More...

#include <dbw_state_machine.hpp>

Public Member Functions

 DbwStateMachine (uint16_t dbw_disabled_debounce)
 Default constructor. More...
 
 ~DbwStateMachine ()=default
 Destructor. More...
 
bool8_t enabled () const
 Returns true if state is ENABLED, ENABLE_SENT, or ENABLE_REQUESTED with conditions. More...
 
DbwState get_state () const
 Returns current internal state. More...
 
void dbw_feedback (bool8_t enabled)
 Notifies the state machine that feedback was received from the DBW system. More...
 
void control_cmd_sent ()
 Notifies the state machine that a control command was sent to the DBW system. More...
 
void state_cmd_sent ()
 Notifies the state machine that a state command was sent to the DBW system. More...
 
void user_request (bool8_t enable)
 The user has requested the DBW system to enable (true) or disable (false) More...
 

Detailed Description

Class for maintaining the DBW state.

Constructor & Destructor Documentation

◆ DbwStateMachine()

autoware::drivers::vehicle_interface::DbwStateMachine::DbwStateMachine ( uint16_t  dbw_disabled_debounce)
explicit

Default constructor.

Parameters
[in]dbw_disabled_debounceIf state = ENABLE_SENT and DBW reports DISABLED, debounce this many msgs // NOLINT

◆ ~DbwStateMachine()

autoware::drivers::vehicle_interface::DbwStateMachine::~DbwStateMachine ( )
default

Destructor.

Member Function Documentation

◆ control_cmd_sent()

void autoware::drivers::vehicle_interface::DbwStateMachine::control_cmd_sent ( )

Notifies the state machine that a control command was sent to the DBW system.

◆ dbw_feedback()

void autoware::drivers::vehicle_interface::DbwStateMachine::dbw_feedback ( bool8_t  enabled)

Notifies the state machine that feedback was received from the DBW system.

Parameters
[in]enabledIf true, DBW system reports enabled. If false, DBW system reports disabled

◆ enabled()

bool8_t autoware::drivers::vehicle_interface::DbwStateMachine::enabled ( ) const

Returns true if state is ENABLED, ENABLE_SENT, or ENABLE_REQUESTED with conditions.

◆ get_state()

DbwState autoware::drivers::vehicle_interface::DbwStateMachine::get_state ( ) const

Returns current internal state.

Returns
A DbwState object representing the current state

◆ state_cmd_sent()

void autoware::drivers::vehicle_interface::DbwStateMachine::state_cmd_sent ( )

Notifies the state machine that a state command was sent to the DBW system.

◆ user_request()

void autoware::drivers::vehicle_interface::DbwStateMachine::user_request ( bool8_t  enable)

The user has requested the DBW system to enable (true) or disable (false)

Parameters
[in]enableIf true, request enable. If false, request disable

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