11 #include <unordered_map>
22 const std::unordered_map<std::string, cras::priority_mux::LockConfig>& lockConfigs,
25 cras::
HasLogger(log), topicConfigs(topicConfigs), lockConfigs(lockConfigs), setTimer(setTimerFn),
26 noneTopic(noneTopic), nonePriority(nonePriority), lastActivePriority(nonePriority)
32 CRAS_DEBUG(
"Starting with no selected topic for output topic %s.", outAndSelectedTopic.first.c_str());
34 for (
const auto& nameAndLockConfig : this->lockConfigs)
36 const auto& name = nameAndLockConfig.first;
37 const auto& config = nameAndLockConfig.second;
39 this->
setTimer(name, config.timeout);
50 CRAS_ERROR(
"Priority mux called with topic %s which is not configured.", inTopic.c_str());
54 const auto& topicConfig = it->second;
55 const auto& priority = topicConfig.priority;
56 const auto key = std::make_pair(priority, inTopic);
62 const auto remainingTimeout = topicConfig.timeout + (stamp - now);
66 this->
setTimer(inTopic, remainingTimeout);
72 const auto& disabledStamp = disableIt->second;
73 if (now < disabledStamp + topicConfig.timeout)
86 CRAS_ERROR(
"Priority mux called with topic %s which is not configured.", inTopic.c_str());
90 const auto& topicConfig = it->second;
91 const auto& priority = topicConfig.priority;
92 const auto key = std::make_pair(priority, inTopic);
104 const auto remainingTimeout = topicConfig.timeout + (stamp - now);
108 this->
setTimer(
"__disable_" + inTopic, remainingTimeout);
117 CRAS_ERROR(
"Priority mux called with lock topic %s which is not configured.", topic.c_str());
121 const auto& lockConfig = it->second;
122 const auto& priority = lockConfig.priority;
123 const auto& timeout = lockConfig.timeout;
125 const auto key = std::make_pair(priority, topic);
132 const auto remainingTimeout = timeout + (stamp - now);
144 for (
auto it = this->
lastReceiveStamps.crbegin(); it != this->lastReceiveStamps.crend(); ++it)
146 const auto& itPriority = it->first.first;
147 const auto& itTopic = it->first.second;
149 const auto& itStamp = it->second;
150 if (now < itStamp + itConfig.timeout)
156 const auto& disabledStamp = disableIt->second;
157 if (now < disabledStamp + itConfig.timeout)
162 topicsPriority = itPriority;
178 if (topicsPriority >= lockedPriority)
182 const auto& config = topicAndConfig.second;
183 if (config.priority != topicsPriority)
185 this->lastSelectedTopics[config.outTopic] = topicAndConfig.first;
189 for (
const auto& outAndSelectedTopic : this->lastSelectedTopics)
191 if (lastTopics[outAndSelectedTopic.first] != outAndSelectedTopic.second)
192 CRAS_DEBUG(
"Choosing topic %s instead of %s for output topic %s.", outAndSelectedTopic.second.c_str(),
193 lastTopics[outAndSelectedTopic.first].c_str(), outAndSelectedTopic.first.c_str());
200 for (
auto it = this->
lastLockStamps.crbegin(); it != this->lastLockStamps.crend(); ++it)
202 const auto& itPriority = it->first.first;
203 const auto& itTopic = it->first.second;
204 const auto& itStamp = it->second;
206 const auto& itTimeout = itConfig.timeout;
207 const auto key = std::make_pair(itPriority, itTopic);
210 highestLockedPriority = itPriority;
214 return highestLockedPriority;
240 for (
const auto& topicAndLockConfig : this->
lockConfigs)
242 const auto key = std::make_pair(topicAndLockConfig.second.priority, topicAndLockConfig.first);
257 CRAS_ERROR(
"Priority mux called with topic %s which is not configured.", inTopic.c_str());
261 const auto& config = it->second;
263 const auto disableIt = this->
disabledStamps.find(std::make_pair(config.priority, it->first));
266 const auto& disabledStamp = disableIt->second;
267 return now >= disabledStamp + config.timeout;