
Public Member Functions | |
| def | __init__ (self, request, message) |
| def | execute (self, userdata) |
| def | on_enter (self, userdata) |
Private Attributes | |
| _action_topic | |
| _client | |
| _connected | |
| _message | |
| _received | |
| _request | |
Implements a state where the state machine needs an input from the operator. Requests of different types, such as requesting a waypoint, a template, or a pose, can be specified. -- request uint8 One of the custom-defined values to specify the type of request. -- message string Message displayed to the operator to let him know what to do. #> data object The data provided by the operator. The exact type depends on the request. <= received Returned as soon as valid data is available. <= aborted The operator declined to provide the requested data. <= no_connection No request could be sent to the operator. <= data_error Data has been received, but could not be deserialized successfully.
Definition at line 9 of file input_state.py.
| def flexbe_states.input_state.InputState.__init__ | ( | self, | |
| request, | |||
| message | |||
| ) |
Constructor
Definition at line 25 of file input_state.py.
| def flexbe_states.input_state.InputState.execute | ( | self, | |
| userdata | |||
| ) |
Definition at line 39 of file input_state.py.
| def flexbe_states.input_state.InputState.on_enter | ( | self, | |
| userdata | |||
| ) |
Definition at line 62 of file input_state.py.
|
private |
Definition at line 31 of file input_state.py.
|
private |
Definition at line 32 of file input_state.py.
|
private |
Definition at line 36 of file input_state.py.
|
private |
Definition at line 35 of file input_state.py.
|
private |
Definition at line 37 of file input_state.py.
|
private |
Definition at line 34 of file input_state.py.