C++ YASMIN (Yet Another State MachINe)
|
Template class to monitor a ROS 2 topic and process incoming messages. More...
#include <monitor_state.hpp>
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. | |
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.
MsgT | The message type of the topic to subscribe to. |
|
private |
Function type for handling messages from topic.
|
inline |
Construct a new MonitorState with specific QoS and message queue settings.
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 |
Construct a new MonitorState with default QoS and message queue.
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 |
Construct a new MonitorState with specific QoS, message queue, and timeout.
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 |
Construct a new MonitorState with ROS 2 node, specific QoS, message queue, and timeout.
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. |
|
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
.
msg | The message received from the topic. |
|
inlineoverridevirtual |
Execute the monitoring operation and process the first received message.
blackboard | A shared pointer to the blackboard for data storage. |
Reimplemented from yasmin::State.
|
private |
Callback function to handle incoming messages.
|
private |
Flag to control message monitoring state.
|
private |
List to store queued messages.
|
private |
Maximum number of messages to queue.
|
private |
ROS 2 node pointer.
|
private |
Subscription to the ROS 2 topic.
|
private |
Time in microseconds to wait between checks.
|
private |
Timeout in seconds for message reception.
|
private |
Name of the topic to monitor.