|
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 (const std::string &topic_name, const std::set< std::string > &outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos=10, int msg_queue=10, int timeout=-1, int maximum_retry=3) | |
| Construct a new MonitorState with specific QoS, message queue, and timeout. | |
| MonitorState (const std::string &topic_name, const std::set< std::string > &outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos=10, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr, int msg_queue=10, int timeout=-1, int maximum_retry=3) | |
| Construct a new MonitorState with specific QoS, message queue, and timeout. | |
| MonitorState (const rclcpp::Node::SharedPtr &node, const std::string &topic_name, const std::set< std::string > &outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos=10, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr, int msg_queue=10, int timeout=-1, int maximum_retry=3) | |
| 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. | |
| void | cancel_state () |
| Cancel the current monitor state. | |
Public Member Functions inherited from yasmin::State | |
| State (const std::set< std::string > &outcomes) | |
| Constructs a State with a set of possible outcomes. | |
| StateStatus | get_status () const |
| Gets the current status of the state. | |
| bool | is_idle () const |
| Checks if the state is idle. | |
| bool | is_running () const |
| Checks if the state is currently running. | |
| bool | is_canceled () const |
| Checks if the state has been canceled. | |
| bool | is_completed () const |
| Checks if the state has completed execution. | |
| std::string | operator() (std::shared_ptr< blackboard::Blackboard > blackboard) |
| Executes the state and returns the outcome. | |
| 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. | |
Protected Attributes | |
| rclcpp::Node::SharedPtr | node_ |
| Shared pointer to the ROS 2 node. | |
Protected Attributes inherited from yasmin::State | |
| std::set< std::string > | outcomes |
| The possible outcomes of this state. | |
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 | |
| std::shared_ptr< rclcpp::Subscription< MsgT > > | sub |
| std::string | topic_name |
| rclcpp::QoS | qos |
| std::vector< std::shared_ptr< MsgT > > | msg_list |
| MonitorHandler | monitor_handler |
| int | msg_queue |
| int | timeout |
| int | maximum_retry |
| std::condition_variable | msg_cond |
| Condition variable for action completion. | |
| std::mutex | msg_mutex |
| Mutex for protecting action completion. | |
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, 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. |
| maximum_retry | Maximum retries of the service if it returns timeout. Default is 3. |
|
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. |
| callback_group | The callback group for the subscription. |
| msg_queue | The maximum number of messages to queue. |
| timeout | The time in seconds to wait for messages before timing out. |
| maximum_retry | Maximum retries of the service if it returns timeout. Default is 3. |
|
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. |
| maximum_retry | Maximum retries of the service if it returns timeout. Default is 3. |
|
inlineprivate |
Callback function for receiving messages from the subscribed topic.
Adds the message to msg_list maintaining a maximum queue size of msg_queue.
| msg | The message received from the topic. |
|
inlinevirtual |
Cancel the current monitor state.
This function cancels the ongoing monitor.
Reimplemented from yasmin::State.
|
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 |
Maximum number of retries.
|
private |
Callback function to handle incoming messages.
|
private |
Condition variable for action completion.
|
private |
List to store queued messages.
|
private |
Mutex for protecting action completion.
|
private |
Maximum number of messages to queue.
|
protected |
Shared pointer to the ROS 2 node.
|
private |
Quality of Service settings for the topic.
|
private |
Subscription to the ROS 2 topic.
|
private |
Timeout in seconds for message reception.
|
private |
Name of the topic to monitor.