Template Class MonitorState

Inheritance Relationships

Base Type

  • public yasmin::State

Class Documentation

template<typename MsgT>
class MonitorState : public yasmin::State

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:

MsgT – The message type of the topic to subscribe to.

Public Functions

inline 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.

Parameters:
  • topic_name – The name of the topic to monitor.

  • outcomes – A set of possible outcomes for this state.

  • monitor_handler – A callback handler to process incoming messages.

  • qos – Quality of Service settings for the topic.

  • msg_queue – The maximum number of messages to queue.

inline MonitorState(std::string topic_name, std::set<std::string> outcomes, MonitorHandler monitor_handler)

Construct a new MonitorState with default QoS and message queue.

Parameters:
  • topic_name – The name of the topic to monitor.

  • outcomes – A set of possible outcomes for this state.

  • monitor_handler – A callback handler to process incoming messages.

inline 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.

Parameters:
  • topic_name – The name of the topic to monitor.

  • outcomes – A set of possible outcomes for this state.

  • monitor_handler – A callback handler to process incoming messages.

  • qos – Quality of Service settings for the topic.

  • msg_queue – The maximum number of messages to queue.

  • timeout – The time in seconds to wait for messages before timing out.

inline 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.

Parameters:
  • node – The ROS 2 node.

  • topic_name – The name of the topic to monitor.

  • outcomes – A set of possible outcomes for this state.

  • monitor_handler – A callback handler to process incoming messages.

  • qos – Quality of Service settings for the topic.

  • msg_queue – The maximum number of messages to queue.

  • timeout – The time in seconds to wait for messages before timing out.

inline std::string execute(std::shared_ptr<yasmin::blackboard::Blackboard> blackboard) override

Execute the monitoring operation and process the first received message.

Parameters:

blackboard – A shared pointer to the blackboard for data storage.

Returns:

A string outcome indicating the result of the monitoring operation.