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 <functional>
21#include <memory>
22#include <set>
23#include <string>
24#include <vector>
25
26#include "rclcpp/rclcpp.hpp"
27
29#include "yasmin/state.hpp"
32
33using std::placeholders::_1;
34
35namespace yasmin_ros {
36
46template <typename MsgT> class MonitorState : public yasmin::State {
47
49 using MonitorHandler = std::function<std::string(
50 std::shared_ptr<yasmin::blackboard::Blackboard>, std::shared_ptr<MsgT>)>;
51
52public:
63 MonitorState(std::string topic_name, std::set<std::string> outcomes,
64 MonitorHandler monitor_handler, rclcpp::QoS qos, int msg_queue)
66 -1) {}
67
75 MonitorState(std::string topic_name, std::set<std::string> outcomes,
78
90 MonitorState(std::string topic_name, std::set<std::string> outcomes,
91 MonitorHandler monitor_handler, rclcpp::QoS qos, int msg_queue,
92 int timeout)
95
108 MonitorState(const rclcpp::Node::SharedPtr &node, std::string topic_name,
109 std::set<std::string> outcomes, MonitorHandler monitor_handler,
110 rclcpp::QoS qos, int msg_queue, int timeout)
113 time_to_wait(1000) {
114
115 // set outcomes
116 if (timeout > 0) {
118 } else {
119 this->outcomes = {};
120 }
121
122 if (outcomes.size() > 0) {
123 for (std::string outcome : outcomes) {
124 this->outcomes.insert(outcome);
125 }
126 }
127
128 if (node == nullptr) {
130 } else {
131 this->node_ = node;
132 }
133
134 // create subscriber
135 this->sub = this->node_->template create_subscription<MsgT>(
136 topic_name, qos, std::bind(&MonitorState::callback, this, _1));
137 }
138
146 std::string
147 execute(std::shared_ptr<yasmin::blackboard::Blackboard> blackboard) override {
148
149 float elapsed_time = 0;
150 this->msg_list.clear();
151 this->monitoring = true;
152
153 while (this->msg_list.empty()) {
154 std::this_thread::sleep_for(
155 std::chrono::microseconds(this->time_to_wait));
156
157 if (this->timeout > 0) {
158
159 if (elapsed_time / 1e6 >= this->timeout) {
160 this->monitoring = false;
161 RCLCPP_WARN(this->node_->get_logger(),
162 "Timeout reached, topic '%s' is not available",
163 this->topic_name.c_str());
165 }
166
167 elapsed_time += this->time_to_wait;
168 }
169 }
170
171 RCLCPP_INFO(this->node_->get_logger(), "Processing msg from topic '%s'",
172 this->topic_name.c_str());
173 std::string outcome =
174 this->monitor_handler(blackboard, this->msg_list.at(0));
175 this->msg_list.erase(this->msg_list.begin());
176
177 this->monitoring = false;
178 return outcome;
179 }
180
181private:
182 rclcpp::Node::SharedPtr node_;
183 std::shared_ptr<rclcpp::Subscription<MsgT>>
185 std::vector<std::shared_ptr<MsgT>>
188 std::string topic_name;
204 void callback(const typename MsgT::SharedPtr msg) {
205
206 if (this->monitoring) {
207 this->msg_list.push_back(msg);
208
209 if ((int)this->msg_list.size() >= this->msg_queue) {
210 this->msg_list.erase(this->msg_list.begin());
211 }
212 }
213 }
214};
215
216} // namespace yasmin_ros
217
218#endif // YASMIN_ROS__MONITOR_STATE_HPP
Represents a state in a state machine.
Definition state.hpp:42
std::set< std::string > outcomes
The possible outcomes of this state.
Definition state.hpp:46
State(std::set< std::string > outcomes)
Constructs a State with a set of possible outcomes.
Definition state.cpp:27
Template class to monitor a ROS 2 topic and process incoming messages.
Definition monitor_state.hpp:46
std::vector< std::shared_ptr< MsgT > > msg_list
Definition monitor_state.hpp:186
rclcpp::Node::SharedPtr node_
Definition monitor_state.hpp:182
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.
Definition monitor_state.hpp:108
int timeout
Definition monitor_state.hpp:192
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.
Definition monitor_state.hpp:90
MonitorHandler monitor_handler
Definition monitor_state.hpp:190
std::string topic_name
Definition monitor_state.hpp:188
std::shared_ptr< rclcpp::Subscription< MsgT > > sub
Definition monitor_state.hpp:184
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.
Definition monitor_state.hpp:63
int time_to_wait
Definition monitor_state.hpp:194
MonitorState(std::string topic_name, std::set< std::string > outcomes, MonitorHandler monitor_handler)
Construct a new MonitorState with default QoS and message queue.
Definition monitor_state.hpp:75
bool monitoring
Definition monitor_state.hpp:193
std::function< std::string( std::shared_ptr< yasmin::blackboard::Blackboard >, std::shared_ptr< MsgT >)> MonitorHandler
Function type for handling messages from topic.
Definition monitor_state.hpp:49
std::string execute(std::shared_ptr< yasmin::blackboard::Blackboard > blackboard) override
Execute the monitoring operation and process the first received message.
Definition monitor_state.hpp:147
void callback(const typename MsgT::SharedPtr msg)
Callback function for receiving messages from the subscribed topic.
Definition monitor_state.hpp:204
int msg_queue
Definition monitor_state.hpp:191
static std::shared_ptr< YasminNode > get_instance()
Provides access to the singleton instance of YasminNode.
Definition yasmin_node.hpp:73
constexpr char TIMEOUT[]
Constant representing a timed-out action outcome.
Definition basic_outcomes.hpp:63
Definition action_state.hpp:35