C++ YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
yasmin_ros::MonitorState< MsgT > Class Template Reference

Template class to monitor a ROS 2 topic and process incoming messages. More...

#include <monitor_state.hpp>

Inheritance diagram for yasmin_ros::MonitorState< MsgT >:
Collaboration diagram for yasmin_ros::MonitorState< MsgT >:

Public Member Functions

 MonitorState (std::string topic_name, std::set< std::string > outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos, int msg_queue)
 Construct a new MonitorState with specific QoS and message queue settings.
 
 MonitorState (std::string topic_name, std::set< std::string > outcomes, MonitorHandler monitor_handler)
 Construct a new MonitorState with default QoS and message queue.
 
 MonitorState (std::string topic_name, std::set< std::string > outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos, int msg_queue, int timeout)
 Construct a new MonitorState with specific QoS, message queue, and timeout.
 
 MonitorState (const rclcpp::Node::SharedPtr &node, std::string topic_name, std::set< std::string > outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos, int msg_queue, int timeout)
 Construct a new MonitorState with ROS 2 node, specific QoS, message queue, and timeout.
 
std::string execute (std::shared_ptr< yasmin::blackboard::Blackboard > blackboard) override
 Execute the monitoring operation and process the first received message.
 
- Public Member Functions inherited from yasmin::State
 State (std::set< std::string > outcomes)
 Constructs a State with a set of possible outcomes.
 
std::string operator() (std::shared_ptr< blackboard::Blackboard > blackboard)
 Executes the state and returns the outcome.
 
virtual void cancel_state ()
 Cancels the current state execution.
 
bool is_canceled () const
 Checks if the state has been canceled.
 
bool is_running () const
 Checks if the state is currently running.
 
std::set< std::string > const & get_outcomes ()
 Gets the set of possible outcomes for this state.
 
virtual std::string to_string ()
 Converts the state to a string representation.
 

Private Types

using MonitorHandler
 Function type for handling messages from topic.
 

Private Member Functions

void callback (const typename MsgT::SharedPtr msg)
 Callback function for receiving messages from the subscribed topic.
 

Private Attributes

rclcpp::Node::SharedPtr node_
 
std::shared_ptr< rclcpp::Subscription< MsgT > > sub
 
std::vector< std::shared_ptr< MsgT > > msg_list
 
std::string topic_name
 
MonitorHandler monitor_handler
 
int msg_queue
 
int timeout
 
bool monitoring
 
int time_to_wait
 

Additional Inherited Members

- Protected Attributes inherited from yasmin::State
std::set< std::string > outcomes
 The possible outcomes of this state.
 

Detailed Description

template<typename MsgT>
class yasmin_ros::MonitorState< MsgT >

Template class to monitor a ROS 2 topic and process incoming messages.

This class provides functionality to subscribe to a ROS 2 topic of type MsgT, execute a custom monitoring handler, and return specific outcomes based on the messages received.

Template Parameters
MsgTThe message type of the topic to subscribe to.

Member Typedef Documentation

◆ MonitorHandler

template<typename MsgT >
using yasmin_ros::MonitorState< MsgT >::MonitorHandler
private
Initial value:
std::function<std::string(
std::shared_ptr<yasmin::blackboard::Blackboard>, std::shared_ptr<MsgT>)>

Function type for handling messages from topic.

Constructor & Destructor Documentation

◆ MonitorState() [1/4]

template<typename MsgT >
yasmin_ros::MonitorState< MsgT >::MonitorState ( std::string topic_name,
std::set< std::string > outcomes,
MonitorHandler monitor_handler,
rclcpp::QoS qos,
int msg_queue )
inline

Construct a new MonitorState with specific QoS and message queue settings.

Parameters
topic_nameThe name of the topic to monitor.
outcomesA set of possible outcomes for this state.
monitor_handlerA callback handler to process incoming messages.
qosQuality of Service settings for the topic.
msg_queueThe maximum number of messages to queue.

◆ MonitorState() [2/4]

template<typename MsgT >
yasmin_ros::MonitorState< MsgT >::MonitorState ( std::string topic_name,
std::set< std::string > outcomes,
MonitorHandler monitor_handler )
inline

Construct a new MonitorState with default QoS and message queue.

Parameters
topic_nameThe name of the topic to monitor.
outcomesA set of possible outcomes for this state.
monitor_handlerA callback handler to process incoming messages.

◆ MonitorState() [3/4]

template<typename MsgT >
yasmin_ros::MonitorState< MsgT >::MonitorState ( std::string topic_name,
std::set< std::string > outcomes,
MonitorHandler monitor_handler,
rclcpp::QoS qos,
int msg_queue,
int timeout )
inline

Construct a new MonitorState with specific QoS, message queue, and timeout.

Parameters
topic_nameThe name of the topic to monitor.
outcomesA set of possible outcomes for this state.
monitor_handlerA callback handler to process incoming messages.
qosQuality of Service settings for the topic.
msg_queueThe maximum number of messages to queue.
timeoutThe time in seconds to wait for messages before timing out.

◆ MonitorState() [4/4]

template<typename MsgT >
yasmin_ros::MonitorState< MsgT >::MonitorState ( const rclcpp::Node::SharedPtr & node,
std::string topic_name,
std::set< std::string > outcomes,
MonitorHandler monitor_handler,
rclcpp::QoS qos,
int msg_queue,
int timeout )
inline

Construct a new MonitorState with ROS 2 node, specific QoS, message queue, and timeout.

Parameters
nodeThe ROS 2 node.
topic_nameThe name of the topic to monitor.
outcomesA set of possible outcomes for this state.
monitor_handlerA callback handler to process incoming messages.
qosQuality of Service settings for the topic.
msg_queueThe maximum number of messages to queue.
timeoutThe time in seconds to wait for messages before timing out.

Member Function Documentation

◆ callback()

template<typename MsgT >
void yasmin_ros::MonitorState< MsgT >::callback ( const typename MsgT::SharedPtr msg)
inlineprivate

Callback function for receiving messages from the subscribed topic.

Adds the message to msg_list if monitoring is active, maintaining a maximum queue size of msg_queue.

Parameters
msgThe message received from the topic.

◆ execute()

template<typename MsgT >
std::string yasmin_ros::MonitorState< MsgT >::execute ( std::shared_ptr< yasmin::blackboard::Blackboard > blackboard)
inlineoverridevirtual

Execute the monitoring operation and process the first received message.

Parameters
blackboardA shared pointer to the blackboard for data storage.
Returns
A string outcome indicating the result of the monitoring operation.

Reimplemented from yasmin::State.

Member Data Documentation

◆ monitor_handler

template<typename MsgT >
MonitorHandler yasmin_ros::MonitorState< MsgT >::monitor_handler
private

Callback function to handle incoming messages.

◆ monitoring

template<typename MsgT >
bool yasmin_ros::MonitorState< MsgT >::monitoring
private

Flag to control message monitoring state.

◆ msg_list

template<typename MsgT >
std::vector<std::shared_ptr<MsgT> > yasmin_ros::MonitorState< MsgT >::msg_list
private

List to store queued messages.

◆ msg_queue

template<typename MsgT >
int yasmin_ros::MonitorState< MsgT >::msg_queue
private

Maximum number of messages to queue.

◆ node_

template<typename MsgT >
rclcpp::Node::SharedPtr yasmin_ros::MonitorState< MsgT >::node_
private

ROS 2 node pointer.

◆ sub

template<typename MsgT >
std::shared_ptr<rclcpp::Subscription<MsgT> > yasmin_ros::MonitorState< MsgT >::sub
private

Subscription to the ROS 2 topic.

◆ time_to_wait

template<typename MsgT >
int yasmin_ros::MonitorState< MsgT >::time_to_wait
private

Time in microseconds to wait between checks.

◆ timeout

template<typename MsgT >
int yasmin_ros::MonitorState< MsgT >::timeout
private

Timeout in seconds for message reception.

◆ topic_name

template<typename MsgT >
std::string yasmin_ros::MonitorState< MsgT >::topic_name
private

Name of the topic to monitor.


The documentation for this class was generated from the following file: