16#ifndef YASMIN_ROS__MONITOR_STATE_HPP_
17#define YASMIN_ROS__MONITOR_STATE_HPP_
20#include <condition_variable>
26#include "rclcpp/rclcpp.hpp"
35using std::placeholders::_1;
96 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr,
118 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr,
130 for (
const std::string &outcome :
outcomes) {
131 this->outcomes.insert(outcome);
135 if (node ==
nullptr) {
142 rclcpp::SubscriptionOptions options;
143 options.callback_group = callback_group;
144 this->
sub = this->
node_->create_subscription<MsgT>(
158 std::unique_lock<std::mutex> lock(this->
msg_mutex);
159 std::cv_status wait_status = std::cv_status::no_timeout;
174 while (this->
timeout > 0 && wait_status == std::cv_status::timeout) {
182 this->maximum_retry);
183 wait_status = this->
msg_cond.wait_for(
184 lock, std::chrono::seconds(this->
timeout));
196 std::string outcome =
219 std::shared_ptr<rclcpp::Subscription<MsgT>>
sub;
250 void callback(
const typename MsgT::SharedPtr msg) {
252 this->msg_list.push_back(msg);
254 if ((
int)this->msg_list.size() > this->msg_queue) {
255 this->msg_list.erase(this->msg_list.begin());
258 this->msg_cond.notify_one();
std::shared_ptr< Blackboard > SharedPtr
Shared pointer type for Blackboard.
Definition blackboard.hpp:85
Represents a state in a state machine.
Definition state.hpp:46
Outcomes outcomes
The possible outcomes of this state.
Definition state.hpp:50
State(const Outcomes &outcomes)
Shared pointer type for State.
Definition state.cpp:32
bool is_canceled() const noexcept
Checks if the state has been canceled.
Definition state.cpp:52
virtual void cancel_state()
Cancels the current state execution.
Definition state.hpp:141
std::vector< std::shared_ptr< MsgT > > msg_list
List to store queued messages.
Definition monitor_state.hpp:227
void cancel_state() override
Cancel the current monitor state.
Definition monitor_state.hpp:208
rclcpp::Node::SharedPtr node_
Shared pointer to the ROS 2 node.
Definition monitor_state.hpp:215
MonitorState(const std::string &topic_name, const yasmin::Outcomes &outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos=10, int msg_queue=10, int timeout=-1, int maximum_retry=3)
Shared pointer type for MonitorState.
Definition monitor_state.hpp:73
rclcpp::QoS qos
Quality of Service settings for the topic.
Definition monitor_state.hpp:224
int timeout
Timeout in seconds for message reception.
Definition monitor_state.hpp:233
std::function< std::string( yasmin::Blackboard::SharedPtr, std::shared_ptr< MsgT >)> MonitorHandler
Function type for handling messages from topic.
Definition monitor_state.hpp:51
MonitorHandler monitor_handler
Callback function to handle incoming messages.
Definition monitor_state.hpp:229
int maximum_retry
Maximum number of retries.
Definition monitor_state.hpp:235
std::string topic_name
Name of the topic to monitor.
Definition monitor_state.hpp:222
std::shared_ptr< rclcpp::Subscription< MsgT > > sub
Subscription to the ROS 2 topic.
Definition monitor_state.hpp:219
std::string execute(yasmin::Blackboard::SharedPtr blackboard) override
Execute the monitoring operation and process the first received message.
Definition monitor_state.hpp:156
MonitorState(const std::string &topic_name, const yasmin::Outcomes &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.
Definition monitor_state.hpp:94
std::mutex msg_mutex
Mutex for protecting action completion.
Definition monitor_state.hpp:240
void callback(const typename MsgT::SharedPtr msg)
Callback function for receiving messages from the subscribed topic.
Definition monitor_state.hpp:250
std::condition_variable msg_cond
Condition variable for action completion.
Definition monitor_state.hpp:238
int msg_queue
Maximum number of messages to queue.
Definition monitor_state.hpp:231
MonitorState(const rclcpp::Node::SharedPtr &node, const std::string &topic_name, const yasmin::Outcomes &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.
Definition monitor_state.hpp:115
static YasminNode::SharedPtr get_instance()
Provides access to the singleton instance of YasminNode.
Definition yasmin_node.hpp:74
#define YASMIN_LOG_INFO(text,...)
Definition logs.hpp:169
#define YASMIN_LOG_WARN(text,...)
Definition logs.hpp:164
constexpr char CANCEL[]
Constant representing a canceled action outcome.
Definition basic_outcomes.hpp:63
constexpr char TIMEOUT[]
Constant representing a timed-out action outcome.
Definition basic_outcomes.hpp:71
Definition action_state.hpp:37
Definition blackboard.hpp:31
StringSet Outcomes
Set of possible outcomes for states.
Definition types.hpp:77
#define YASMIN_PTR_ALIASES(ClassName)
Macro to define all pointer aliases for a class.
Definition types.hpp:52