Skip to content

Commit f5af462

Browse files
committed
using unordered_map for values and registry of blackboard
1 parent bcf9319 commit f5af462

File tree

4 files changed

+9
-11
lines changed

4 files changed

+9
-11
lines changed

yasmin/include/yasmin/blackboard.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include <mutex>
2424
#include <stdexcept>
2525
#include <string>
26+
#include <unordered_map>
2627

2728
#include "yasmin/logs.hpp"
2829

@@ -64,9 +65,9 @@ class Blackboard {
6465
/// Mutex for thread safety.
6566
mutable std::recursive_mutex mutex;
6667
/// Storage for key-value pairs.
67-
std::map<std::string, std::shared_ptr<void>> values;
68+
std::unordered_map<std::string, std::shared_ptr<void>> values;
6869
/// Storage for type information for each key.
69-
std::map<std::string, std::string> type_registry;
70+
std::unordered_map<std::string, std::string> type_registry;
7071
/// Storage for key remappings.
7172
std::map<std::string, std::string> remappings;
7273

yasmin/include/yasmin/concurrence.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ class Concurrence : public State {
6363
OutcomeMap outcome_map;
6464

6565
/// Stores the intermediate outcomes of the concurrent states
66-
std::map<std::string, std::shared_ptr<std::string>> intermediate_outcome_map;
66+
std::map<std::string, std::string> intermediate_outcome_map;
6767

6868
/// The set of possible outcomes
6969
std::set<std::string> possible_outcomes;

yasmin/src/yasmin/concurrence.cpp

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ Concurrence::Concurrence(
7575
state->to_string() + "'");
7676
}
7777

78-
intermediate_outcome_map.insert({state_name, nullptr});
78+
intermediate_outcome_map.insert({state_name, ""});
7979
}
8080
}
8181
}
@@ -90,8 +90,7 @@ Concurrence::execute(std::shared_ptr<yasmin::Blackboard> blackboard) {
9090
blackboard]() {
9191
std::string outcome = (*state.get())(blackboard);
9292
const std::lock_guard<std::mutex> lock(this->intermediate_outcome_mutex);
93-
this->intermediate_outcome_map[state_name] =
94-
std::make_shared<std::string>(outcome);
93+
this->intermediate_outcome_map[state_name] = outcome;
9594
}));
9695
}
9796

@@ -113,14 +112,13 @@ Concurrence::execute(std::shared_ptr<yasmin::Blackboard> blackboard) {
113112
bool satisfied = true;
114113
for (const auto &[state_name, expected_intermediate_outcome] :
115114
requirements) {
116-
std::shared_ptr<std::string> actual_intermediate_outcome =
115+
std::string actual_intermediate_outcome =
117116
intermediate_outcome_map.find(state_name)->second;
118-
if (actual_intermediate_outcome == nullptr) {
117+
if (actual_intermediate_outcome.empty()) {
119118
throw std::runtime_error("An intermediate outcome for state '" +
120119
state_name + "' was not received.");
121120
}
122-
satisfied &=
123-
*actual_intermediate_outcome == expected_intermediate_outcome;
121+
satisfied &= actual_intermediate_outcome == expected_intermediate_outcome;
124122
}
125123
if (satisfied) {
126124
satisfied_outcomes.insert(outcome);

yasmin_factory/include/yasmin_factory/yasmin_factory.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,6 @@
1616
#ifndef YASMIN_FACTORY__YASMIN_FACTORY_HPP
1717
#define YASMIN_FACTORY__YASMIN_FACTORY_HPP
1818

19-
#include <map>
2019
#include <memory>
2120
#include <set>
2221
#include <string>

0 commit comments

Comments
 (0)