|
Python YASMIN (Yet Another State MachINe)
|


Public Member Functions | |
| None | __init__ (self) |
| None | start_backend_server (self) |
| None | start_ros (self) |
| List | transition_msg_to_list (self, List[Transition] transitions) |
| Dict | state_msg_to_dict (self, State msg) |
| Dict | msg_to_dict (self, StateMachine msg) |
| None | fsm_viewer_cb (self, StateMachine msg) |
| None | emit_fsm_data (self) |
Public Attributes | |
| emit_timer = None | |
| SocketIO | socketio = None |
| fsm_viewer_cb | |
Private Attributes | |
| ExpiringDict | __fsm_dict = ExpiringDict(max_len=300, max_age_seconds=3) |
| A dictionary that stores FSM data with automatic expiration. | |
A ROS 2 node that serves as a viewer for the finite state machines (FSMs) using a Flask web server. This class subscribes to FSM updates and serves them over HTTP. It utilizes a dictionary with expiring entries to manage the FSM data.
| None yasmin_viewer.yasmin_viewer_node.YasminViewerNode.__init__ | ( | self | ) |
Initializes the YasminViewerNode node. Declares parameters for the host and port, sets up the expiring dictionary, starts the subscriber thread, and initializes the backend server.
| None yasmin_viewer.yasmin_viewer_node.YasminViewerNode.emit_fsm_data | ( | self | ) |
Emits the current FSM data to connected clients via socket.io.
| None yasmin_viewer.yasmin_viewer_node.YasminViewerNode.fsm_viewer_cb | ( | self, | |
| StateMachine | msg ) |
Callback function for processing incoming StateMachine messages. Waits for the server to start before storing the received FSM data. :param msg: The StateMachine message containing the FSM data.
| Dict yasmin_viewer.yasmin_viewer_node.YasminViewerNode.msg_to_dict | ( | self, | |
| StateMachine | msg ) |
Converts a StateMachine message to a list of dictionaries. :param msg: The StateMachine message to convert. :return: A list of dictionaries representing the states in the StateMachine.
| None yasmin_viewer.yasmin_viewer_node.YasminViewerNode.start_backend_server | ( | self | ) |
Initializes and starts the Flask backend server. Sets up the routes for serving static files and retrieving FSM data. :raises Exception: If the server fails to start.
| None yasmin_viewer.yasmin_viewer_node.YasminViewerNode.start_ros | ( | self | ) |
Subscribes to the FSM state updates and starts the ROS spinning. This method creates a subscription to the '/fsm_viewer' topic and processes incoming messages. :raises ExternalShutdownException: If the ROS 2 node is externally shutdown.
| Dict yasmin_viewer.yasmin_viewer_node.YasminViewerNode.state_msg_to_dict | ( | self, | |
| State | msg ) |
Converts a State message to a dictionary representation. :param msg: The State message to convert. :return: A dictionary containing state attributes.
| List yasmin_viewer.yasmin_viewer_node.YasminViewerNode.transition_msg_to_list | ( | self, | |
| List[Transition] | transitions ) |
Converts a list of Transition messages to a list. :param transitions: A list of Transition messages to convert. :return: A list mapping outcomes to states.
|
private |
A dictionary that stores FSM data with automatic expiration.
| yasmin_viewer.yasmin_viewer_node.YasminViewerNode.emit_timer = None |
| yasmin_viewer.yasmin_viewer_node.YasminViewerNode.fsm_viewer_cb |
| SocketIO yasmin_viewer.yasmin_viewer_node.YasminViewerNode.socketio = None |