16#ifndef YASMIN_ROS__MONITOR_STATE_HPP
17#define YASMIN_ROS__MONITOR_STATE_HPP
26#include "rclcpp/rclcpp.hpp"
33using std::placeholders::_1;
50 std::shared_ptr<yasmin::blackboard::Blackboard>, std::shared_ptr<MsgT>)>;
123 for (std::string outcome :
outcomes) {
124 this->outcomes.insert(outcome);
128 if (node ==
nullptr) {
135 this->
sub = this->
node_->template create_subscription<MsgT>(
147 execute(std::shared_ptr<yasmin::blackboard::Blackboard> blackboard)
override {
149 float elapsed_time = 0;
154 std::this_thread::sleep_for(
159 if (elapsed_time / 1e6 >= this->
timeout) {
161 RCLCPP_WARN(this->
node_->get_logger(),
162 "Timeout reached, topic '%s' is not available",
163 this->topic_name.c_str());
171 RCLCPP_INFO(this->
node_->get_logger(),
"Processing msg from topic '%s'",
172 this->topic_name.c_str());
173 std::string outcome =
183 std::shared_ptr<rclcpp::Subscription<MsgT>>
185 std::vector<std::shared_ptr<MsgT>>
204 void callback(
const typename MsgT::SharedPtr msg) {
206 if (this->monitoring) {
209 if ((
int)this->
msg_list.size() >= this->msg_queue) {
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