Modulo 5.0.0
Loading...
Searching...
No Matches
PredicatesListener.cpp
1#include "modulo_utils/testutils/PredicatesListener.hpp"
2
3namespace modulo_utils::testutils {
4
5PredicatesListener::PredicatesListener(
6 const std::string& node, const std::vector<std::string>& predicates, const rclcpp::NodeOptions& node_options)
7 : rclcpp::Node("predicates_listener", node_options) {
8 this->received_future_ = this->received_.get_future();
9 for (const auto& predicate : predicates) {
10 this->predicates_.insert_or_assign(predicate, false);
11 }
12 this->subscription_ = this->create_subscription<modulo_interfaces::msg::PredicateCollection>(
13 "/predicates", 10, [this, node](const std::shared_ptr<modulo_interfaces::msg::PredicateCollection> message) {
14 if (message->node == node) {
15 for (const auto& predicate_msg : message->predicates) {
16 if (this->predicates_.find(predicate_msg.predicate) != this->predicates_.end()) {
17 this->predicates_.at(predicate_msg.predicate) = predicate_msg.value;
18 if (predicate_msg.value) {
19 this->received_.set_value();
20 }
21 }
22 }
23 }
24 });
25}
26
27void PredicatesListener::reset_future() {
28 this->received_ = std::promise<void>();
29 this->received_future_ = this->received_.get_future();
30}
31
32const std::shared_future<void>& PredicatesListener::get_predicate_future() const {
33 return this->received_future_;
34}
35
36const std::map<std::string, bool>& PredicatesListener::get_predicate_values() const {
37 return this->predicates_;
38}
39}// namespace modulo_utils::testutils