Class YasminViewerPub
Defined in File yasmin_viewer_pub.hpp
Class Documentation
-
class YasminViewerPub
Publishes state machine data for visualization.
Public Functions
Constructs YasminViewerPub with a given ROS 2 node, state machine name, and state machine instance.
- Parameters:
node – Shared pointer to the ROS 2 node.
fsm_name – Name of the finite state machine.
fsm – Shared pointer to the StateMachine instance to be published.
Constructs YasminViewerPub with a default ROS 2 node instance, state machine name, and state machine instance.
- Parameters:
fsm_name – Name of the finite state machine.
fsm – Shared pointer to the StateMachine instance to be published.
-
std::vector<yasmin_msgs::msg::Transition> parse_transitions(std::map<std::string, std::string> transitions)
Parses transitions from a map of transitions and returns a list of Transition messages.
- Parameters:
transitions – Map where keys are transition outcomes, and values are the next states.
- Returns:
Vector of Transition messages.
Parses a state and its transitions to add it to the list of state messages.
- Parameters:
name – Name of the state to be parsed.
state – Shared pointer to the State instance.
transitions – Map of transitions associated with this state.
states_list – Vector to which the parsed State message will be added.
parent – ID of the parent state.
-
void publish_data()
Publishes the data of the finite state machine to the associated ROS topic.
- Throws:
std::exception – if state machine validation fails.