|
| None | __init__ (self, StateMachine fsm, str fsm_name="", int rate=4, Node node=None) |
| |
| None | cleanup (self) |
| |
| List[TransitionMsg] | parse_transitions (self, Dict[str, str] transitions) |
| |
| None | parse_state (self, str state_name, Dict[str, Any] state_info, List[StateMsg] states_list, int parent=-1) |
| |
| Dict[str, Dict[str, str]] | parse_concurrence_transitions (self, Concurrence concurrence) |
| |
|
| Node | _node = node |
| | The ROS 2 node instance used for publishing.
|
| |
| str | _fsm_name = fsm_name |
| | The name of the finite state machine.
|
| |
| StateMachine | _fsm = fsm |
| | The finite state machine to be published.
|
| |
| Node | _pub = self._node.create_publisher(StateMachineMsg, "/fsm_viewer", 10) |
| | The publisher for the state machine messages.
|
| |
| Node | _timer = self._node.create_timer(1 / rate, self._publish_data) |
| | A timer to periodically publish the FSM state.
|
| |
A class to publish the state of a Finite State Machine (FSM) for visualization.
◆ __init__()
| None yasmin_viewer.yasmin_viewer_pub.YasminViewerPub.__init__ |
( |
| self, |
|
|
StateMachine | fsm, |
|
|
str | fsm_name = "", |
|
|
int | rate = 4, |
|
|
Node | node = None ) |
Initializes the YasminViewerPub instance.
Args:
fsm_name (str): The name of the FSM.
fsm (StateMachine): The FSM instance to be published.
rate (int): The rate in Hz at which to publish updates. Defaults to 4.
node (Node, optional): A custom Node instance. If None, a new YasminNode is created.
Raises:
ValueError: If fsm_name is empty.
◆ _publish_data()
| None yasmin_viewer.yasmin_viewer_pub.YasminViewerPub._publish_data |
( |
| self | ) |
|
|
protected |
Publishes the current state of the FSM.
This method validates the FSM, gathers its state data, and publishes it.
If validation fails, an error message is logged.
Returns:
None
Raises:
Exception: If the FSM validation fails, an error is logged and the function exits without publishing.
◆ cleanup()
| None yasmin_viewer.yasmin_viewer_pub.YasminViewerPub.cleanup |
( |
| self | ) |
|
Cleans up resources used by the YasminViewerPub instance.
◆ parse_concurrence_transitions()
| Dict[str, Dict[str, str]] yasmin_viewer.yasmin_viewer_pub.YasminViewerPub.parse_concurrence_transitions |
( |
| self, |
|
|
Concurrence
| concurrence ) |
Converts a concurrence outcome map into transition-like information for visualization.
In concurrence, transitions are based on outcome combinations rather than direct state-to-state transitions.
This method creates pseudo-transitions that represent the outcome mapping logic.
Args:
concurrence (Concurrence): The concurrence state to parse transitions from.
Returns:
List[TransitionMsg]: A list of TransitionMsg representing the concurrence outcome mappings.
◆ parse_state()
| None yasmin_viewer.yasmin_viewer_pub.YasminViewerPub.parse_state |
( |
| self, |
|
|
str | state_name, |
|
|
Dict[str, Any] | state_info, |
|
|
List[StateMsg] | states_list, |
|
|
int | parent = -1 ) |
Recursively parses a state and its transitions, adding the resulting StateMsg to the states list.
Args:
state_name (str): The name of the state.
state_info (Dict[str, str]): Information about the state, including its transitions.
states_list (List[StateMsg]): A list to which the parsed StateMsg will be appended.
parent (int, optional): The ID of the parent state. Defaults to -1.
Returns:
None
◆ parse_transitions()
| List[TransitionMsg] yasmin_viewer.yasmin_viewer_pub.YasminViewerPub.parse_transitions |
( |
| self, |
|
|
Dict[str, str] | transitions ) |
Converts a dictionary of transitions into a list of TransitionMsg.
Args:
transitions (Dict[str, str]): A dictionary where keys are outcome names and values are state names.
Returns:
List[TransitionMsg]: A list of TransitionMsg representing the FSM transitions.
◆ _fsm
| yasmin_viewer.yasmin_viewer_pub.YasminViewerPub._fsm = fsm |
|
protected |
The finite state machine to be published.
◆ _fsm_name
| yasmin_viewer.yasmin_viewer_pub.YasminViewerPub._fsm_name = fsm_name |
|
protected |
The name of the finite state machine.
◆ _node
| Node yasmin_viewer.yasmin_viewer_pub.YasminViewerPub._node = node |
|
protected |
The ROS 2 node instance used for publishing.
◆ _pub
| yasmin_viewer.yasmin_viewer_pub.YasminViewerPub._pub = self._node.create_publisher(StateMachineMsg, "/fsm_viewer", 10) |
|
protected |
The publisher for the state machine messages.
◆ _timer
| yasmin_viewer.yasmin_viewer_pub.YasminViewerPub._timer = self._node.create_timer(1 / rate, self._publish_data) |
|
protected |
A timer to periodically publish the FSM state.
The documentation for this class was generated from the following file: