C++ YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
yasmin_viewer::YasminViewerPub Class Reference

Publishes state machine data for visualization. More...

#include <yasmin_viewer_pub.hpp>

Collaboration diagram for yasmin_viewer::YasminViewerPub:

Public Member Functions

 YasminViewerPub (const rclcpp::Node::SharedPtr &node, yasmin::StateMachine::SharedPtr fsm, const std::string &fsm_name)
 Constructs YasminViewerPub with a given ROS 2 node, state machine name, and state machine instance.
 
 YasminViewerPub (yasmin::StateMachine::SharedPtr fsm, const std::string &fsm_name)
 Constructs YasminViewerPub with a default ROS 2 node instance, state machine name, and state machine instance.
 
 YasminViewerPub (const rclcpp::Node::SharedPtr &node, yasmin::StateMachine::SharedPtr fsm)
 Constructs YasminViewerPub with a given ROS 2 node, state machine name, and state machine instance.
 
 YasminViewerPub (yasmin::StateMachine::SharedPtr 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 (const yasmin::Transitions &transitions) const
 Parses transitions from a map of transitions and returns a list of Transition messages.
 
std::map< std::string, std::vector< yasmin_msgs::msg::Transition > > parse_concurrence_transitions (yasmin::Concurrence::SharedPtr concurrence) const
 Parses concurrence transitions from outcome map to transition-like information.
 
void parse_state (const std::string &name, yasmin::State::SharedPtr state, const yasmin::Transitions &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.
 

Private Attributes

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.
 
yasmin::StateMachine::SharedPtr fsm
 Shared pointer to the state machine.
 
std::string fsm_name
 Name of the finite state machine.
 

Detailed Description

Publishes state machine data for visualization.

Constructor & Destructor Documentation

◆ YasminViewerPub() [1/4]

YasminViewerPub::YasminViewerPub ( const rclcpp::Node::SharedPtr & node,
yasmin::StateMachine::SharedPtr fsm,
const std::string & fsm_name )

Constructs YasminViewerPub with a given ROS 2 node, state machine name, and state machine instance.

Parameters
nodeShared pointer to the ROS 2 node.
fsm_nameName of the finite state machine.
fsmShared pointer to the StateMachine instance to be published.

◆ YasminViewerPub() [2/4]

YasminViewerPub::YasminViewerPub ( yasmin::StateMachine::SharedPtr fsm,
const std::string & fsm_name )

Constructs YasminViewerPub with a default ROS 2 node instance, state machine name, and state machine instance.

Parameters
fsm_nameName of the finite state machine.
fsmShared pointer to the StateMachine instance to be published.

◆ YasminViewerPub() [3/4]

YasminViewerPub::YasminViewerPub ( const rclcpp::Node::SharedPtr & node,
yasmin::StateMachine::SharedPtr fsm )

Constructs YasminViewerPub with a given ROS 2 node, state machine name, and state machine instance.

Parameters
nodeShared pointer to the ROS 2 node.
fsmShared pointer to the StateMachine instance to be published.

◆ YasminViewerPub() [4/4]

YasminViewerPub::YasminViewerPub ( yasmin::StateMachine::SharedPtr fsm)

Constructs YasminViewerPub with a default ROS 2 node instance, state machine name, and state machine instance.

Parameters
fsmShared pointer to the StateMachine instance to be published.

Member Function Documentation

◆ parse_concurrence_transitions()

std::map< std::string, std::vector< yasmin_msgs::msg::Transition > > YasminViewerPub::parse_concurrence_transitions ( yasmin::Concurrence::SharedPtr concurrence) const

Parses concurrence transitions from outcome map to transition-like information.

Parameters
concurrenceShared pointer to the Concurrence state.
Returns
Map of state names to their transition vectors.

◆ parse_state()

void YasminViewerPub::parse_state ( const std::string & name,
yasmin::State::SharedPtr state,
const yasmin::Transitions & 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.

Parameters
nameName of the state to be parsed.
stateShared pointer to the State instance.
transitionsMap of transitions associated with this state.
states_listVector to which the parsed State message will be added.
parentID of the parent state.

◆ parse_transitions()

std::vector< yasmin_msgs::msg::Transition > YasminViewerPub::parse_transitions ( const yasmin::Transitions & transitions) const

Parses transitions from a map of transitions and returns a list of Transition messages.

Parameters
transitionsMap where keys are transition outcomes, and values are the next states.
Returns
Vector of Transition messages.

◆ publish_data()

void YasminViewerPub::publish_data ( )

Publishes the data of the finite state machine to the associated ROS topic.

Exceptions
std::exceptionif state machine validation fails.

Member Data Documentation

◆ fsm

yasmin::StateMachine::SharedPtr yasmin_viewer::YasminViewerPub::fsm
private

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: