C++ YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
monitor_state.hpp
Go to the documentation of this file.
1// Copyright (C) 2023 Miguel Ángel González Santamarta
2//
3// This program is free software: you can redistribute it and/or modify
4// it under the terms of the GNU General Public License as published by
5// the Free Software Foundation, either version 3 of the License, or
6// (at your option) any later version.
7//
8// This program is distributed in the hope that it will be useful,
9// but WITHOUT ANY WARRANTY; without even the implied warranty of
10// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11// GNU General Public License for more details.
12//
13// You should have received a copy of the GNU General Public License
14// along with this program. If not, see <https://www.gnu.org/licenses/>.
15
16#ifndef YASMIN_ROS__MONITOR_STATE_HPP_
17#define YASMIN_ROS__MONITOR_STATE_HPP_
18
19#include <chrono>
20#include <condition_variable>
21#include <functional>
22#include <memory>
23#include <string>
24#include <vector>
25
26#include "rclcpp/rclcpp.hpp"
27
28#include "yasmin/blackboard.hpp"
29#include "yasmin/logs.hpp"
30#include "yasmin/state.hpp"
31#include "yasmin/types.hpp"
34
35using std::placeholders::_1;
36
37namespace yasmin_ros {
38
48template <typename MsgT> class MonitorState : public yasmin::State {
49
51 using MonitorHandler = std::function<std::string(
52 yasmin::Blackboard::SharedPtr, std::shared_ptr<MsgT>)>;
53
54public:
59
60
73 MonitorState(const std::string &topic_name, const yasmin::Outcomes &outcomes,
74 MonitorHandler monitor_handler, rclcpp::QoS qos = 10,
75 int msg_queue = 10, int timeout = -1, int maximum_retry = 3)
77 nullptr, msg_queue, timeout, maximum_retry) {}
78
95 MonitorHandler monitor_handler, rclcpp::QoS qos = 10,
96 rclcpp::CallbackGroup::SharedPtr callback_group = nullptr,
97 int msg_queue = 10, int timeout = -1, int maximum_retry = 3)
99 callback_group, msg_queue, timeout, maximum_retry) {}
100
115 MonitorState(const rclcpp::Node::SharedPtr &node,
116 const std::string &topic_name, const yasmin::Outcomes &outcomes,
117 MonitorHandler monitor_handler, rclcpp::QoS qos = 10,
118 rclcpp::CallbackGroup::SharedPtr callback_group = nullptr,
119 int msg_queue = 10, int timeout = -1, int maximum_retry = 3)
123
124 // set outcomes
125 if (timeout > 0) {
126 this->outcomes.insert(basic_outcomes::TIMEOUT);
127 }
128
129 if (outcomes.size() > 0) {
130 for (const std::string &outcome : outcomes) {
131 this->outcomes.insert(outcome);
132 }
133 }
134
135 if (node == nullptr) {
137 } else {
138 this->node_ = node;
139 }
140
141 // Create subscription
142 rclcpp::SubscriptionOptions options;
143 options.callback_group = callback_group;
144 this->sub = this->node_->create_subscription<MsgT>(
145 this->topic_name, this->qos,
146 std::bind(&MonitorState::callback, this, _1), options);
147 }
148
156 std::string execute(yasmin::Blackboard::SharedPtr blackboard) override {
157 int retry_count = 0;
158 std::unique_lock<std::mutex> lock(this->msg_mutex);
159 std::cv_status wait_status = std::cv_status::no_timeout;
160
161 while (this->msg_list.empty()) {
162
163 if (this->timeout > 0) {
164 wait_status =
165 this->msg_cond.wait_for(lock, std::chrono::seconds(this->timeout));
166 } else {
167 this->msg_cond.wait(lock);
168 }
169
170 if (this->is_canceled()) {
172 }
173
174 while (this->timeout > 0 && wait_status == std::cv_status::timeout) {
175 YASMIN_LOG_WARN("Timeout reached, topic '%s' is not available",
176 this->topic_name.c_str());
177
178 if (retry_count < this->maximum_retry) {
179 retry_count++;
180 YASMIN_LOG_WARN("Retrying to wait for topic '%s' (%d/%d)",
181 this->topic_name.c_str(), retry_count,
182 this->maximum_retry);
183 wait_status = this->msg_cond.wait_for(
184 lock, std::chrono::seconds(this->timeout));
185 } else {
187 }
188
189 if (this->is_canceled()) {
191 }
192 }
193 }
194
195 YASMIN_LOG_INFO("Processing msg from topic '%s'", this->topic_name.c_str());
196 std::string outcome =
197 this->monitor_handler(blackboard, this->msg_list.at(0));
198 this->msg_list.erase(this->msg_list.begin());
199
200 return outcome;
201 }
202
208 void cancel_state() override {
209 this->msg_cond.notify_one();
211 }
212
213protected:
215 rclcpp::Node::SharedPtr node_;
216
217private:
219 std::shared_ptr<rclcpp::Subscription<MsgT>> sub;
220
222 std::string topic_name;
224 rclcpp::QoS qos;
225
227 std::vector<std::shared_ptr<MsgT>> msg_list;
236
238 std::condition_variable msg_cond;
240 std::mutex msg_mutex;
241
250 void callback(const typename MsgT::SharedPtr msg) {
251
252 this->msg_list.push_back(msg);
253
254 if ((int)this->msg_list.size() > this->msg_queue) {
255 this->msg_list.erase(this->msg_list.begin());
256 }
257
258 this->msg_cond.notify_one();
259 }
260};
261
262} // namespace yasmin_ros
263
264#endif // YASMIN_ROS__MONITOR_STATE_HPP_
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