Python YASMIN (Yet Another State MachINe)
|
Public Member Functions | |
None | __init__ (self) |
None | start_backend_server (self) |
None | start_subscriber (self) |
Dict | transition_msg_to_dict (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) |
Public Attributes | |
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. Attributes: __fsm_dict (ExpiringDict): A dictionary that stores FSM data with automatic expiration. Methods: start_backend_server(): Initializes and starts the Flask server. start_subscriber(): Subscribes to the FSM state updates. transition_msg_to_dict(tansitions): Converts a list of transitions to a dictionary. state_msg_to_dict(msg): Converts a State message to a dictionary. msg_to_dict(msg): Converts a StateMachine message to a list of dictionaries. fsm_viewer_cb(msg): Callback function for processing FSM updates.
None yasmin_viewer.yasmin_viewer_node.YasminFsmViewerNode.__init__ | ( | self | ) |
Initializes the YasminFsmViewerNode 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.YasminFsmViewerNode.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.YasminFsmViewerNode.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.YasminFsmViewerNode.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.YasminFsmViewerNode.start_subscriber | ( | 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.YasminFsmViewerNode.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.
Dict yasmin_viewer.yasmin_viewer_node.YasminFsmViewerNode.transition_msg_to_dict | ( | self, | |
List[Transition] | transitions ) |
Converts a list of Transition messages to a dictionary. :param transitions: A list of Transition messages to convert. :return: A dictionary mapping outcomes to states.
|
private |
A dictionary that stores FSM data with automatic expiration.
yasmin_viewer.yasmin_viewer_node.YasminFsmViewerNode.fsm_viewer_cb |