Publishes state machine data for visualization.
More...
#include <yasmin_viewer_pub.hpp>
|
| | YasminViewerPub (const rclcpp::Node::SharedPtr &node, std::string fsm_name, std::shared_ptr< yasmin::StateMachine > fsm) |
| | Constructs YasminViewerPub with a given ROS 2 node, state machine name, and state machine instance.
|
| |
| | YasminViewerPub (std::string fsm_name, std::shared_ptr< yasmin::StateMachine > fsm) |
| | Constructs YasminViewerPub with a default ROS 2 node instance, state machine name, and state machine instance.
|
| |
| 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.
|
| |
| void | parse_state (std::string name, std::shared_ptr< yasmin::State > state, std::map< std::string, std::string > transitions, std::vector< yasmin_msgs::msg::State > &states_list, int parent) |
| | Parses a state and its transitions to add it to the list of state messages.
|
| |
| void | publish_data () |
| | Publishes the data of the finite state machine to the associated ROS topic.
|
| |
|
| rclcpp::Node::SharedPtr | node_ |
| | Shared pointer to the ROS 2 node.
|
| |
| rclcpp::Publisher< yasmin_msgs::msg::StateMachine >::SharedPtr | publisher |
| | Publisher for StateMachine messages.
|
| |
| rclcpp::TimerBase::SharedPtr | timer |
| | Timer for periodic publishing.
|
| |
| std::string | fsm_name |
| | Name of the finite state machine.
|
| |
| std::shared_ptr< yasmin::StateMachine > | fsm |
| | Shared pointer to the state machine.
|
| |
Publishes state machine data for visualization.
◆ YasminViewerPub() [1/2]
| YasminViewerPub::YasminViewerPub |
( |
const rclcpp::Node::SharedPtr & | node, |
|
|
std::string | fsm_name, |
|
|
std::shared_ptr< yasmin::StateMachine > | fsm ) |
Constructs YasminViewerPub with a given ROS 2 node, state machine name, and state machine instance.
Constructs YasminViewerPub with a specific ROS node. If the node is nullptr, a singleton instance of YasminNode is used.
- 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. |
◆ YasminViewerPub() [2/2]
| YasminViewerPub::YasminViewerPub |
( |
std::string | fsm_name, |
|
|
std::shared_ptr< yasmin::StateMachine > | fsm ) |
Constructs YasminViewerPub with a default ROS 2 node instance, state machine name, and state machine instance.
Constructs YasminViewerPub by delegating to another constructor with a nullptr node.
- Parameters
-
| fsm_name | Name of the finite state machine. |
| fsm | Shared pointer to the StateMachine instance to be published. |
◆ parse_state()
| void YasminViewerPub::parse_state |
( |
std::string | state_name, |
|
|
std::shared_ptr< yasmin::State > | state, |
|
|
std::map< std::string, std::string > | transitions, |
|
|
std::vector< yasmin_msgs::msg::State > & | states_list, |
|
|
int | parent ) |
Parses a state and its transitions to add it to the list of state messages.
Parses a state and its transitions, adding it to the states list and handling nested FSMs if applicable.
- 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. |
| state_name | Name of the state. |
| state | Shared pointer to the State instance. |
| transitions | Map of transitions related to the state. |
| states_list | Reference to a vector of yasmin_msgs::msg::State to append parsed states. |
| parent | ID of the parent state; -1 for top-level states. |
◆ parse_transitions()
| std::vector< yasmin_msgs::msg::Transition > YasminViewerPub::parse_transitions |
( |
std::map< std::string, std::string > | transitions | ) |
|
Parses transitions from a map of transitions and returns a list of Transition messages.
Parses a map of transition pairs (outcome, state) to a vector of Transition messages.
- Parameters
-
| transitions | Map where keys are transition outcomes, and values are the next states. |
- Returns
- Vector of Transition messages.
- Parameters
-
| transitions | Map containing transition outcomes as keys and next states as values. |
- Returns
- Vector of yasmin_msgs::msg::Transition.
◆ publish_data()
| void YasminViewerPub::publish_data |
( |
| ) |
|
Publishes the data of the finite state machine to the associated ROS topic.
Publishes the state machine data if validation is successful.
- Exceptions
-
| std::exception | if state machine validation fails. |
| std::exception | Thrown if the state machine fails validation. |
◆ fsm
Shared pointer to the state machine.
◆ fsm_name
| std::string yasmin_viewer::YasminViewerPub::fsm_name |
|
private |
Name of the finite state machine.
◆ node_
| rclcpp::Node::SharedPtr yasmin_viewer::YasminViewerPub::node_ |
|
private |
Shared pointer to the ROS 2 node.
◆ publisher
| rclcpp::Publisher<yasmin_msgs::msg::StateMachine>::SharedPtr yasmin_viewer::YasminViewerPub::publisher |
|
private |
Publisher for StateMachine messages.
◆ timer
| rclcpp::TimerBase::SharedPtr yasmin_viewer::YasminViewerPub::timer |
|
private |
Timer for periodic publishing.
The documentation for this class was generated from the following files: