Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

use std::map in topicMap type #546

Open
wants to merge 2 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 5 additions & 5 deletions rmw_zenoh_cpp/src/detail/graph_cache.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,11 +157,11 @@ void GraphCache::update_topic_map_for_put(
return;
}
// The topic exists in the topic_map so we check if the type also exists.
GraphNode::TopicTypeMap::iterator topic_type_map_it = topic_map_it.value().find(
GraphNode::TopicTypeMap::iterator topic_type_map_it = topic_map_it->second.find(
graph_topic_data->info_.type_);
if (topic_type_map_it == topic_map_it->second.end()) {
// First time this topic type is added.
topic_map_it.value().insert(
topic_map_it->second.insert(
std::make_pair(
graph_topic_data->info_.type_,
std::move(topic_qos_map)));
Expand Down Expand Up @@ -445,7 +445,7 @@ void GraphCache::update_topic_map_for_del(
}

GraphNode::TopicTypeMap::iterator cache_topic_type_it =
cache_topic_it.value().find(topic_info.type_);
cache_topic_it->second.find(topic_info.type_);
if (cache_topic_type_it == cache_topic_it->second.end()) {
// If an entity is short-lived, it is possible to receive the liveliness token
// for its deletion before the one for its creation given that Zenoh does not
Expand Down Expand Up @@ -490,7 +490,7 @@ void GraphCache::update_topic_map_for_del(
}
// If the type does not have any qos entries, erase it from the type map.
if (cache_topic_type_it->second.empty()) {
cache_topic_it.value().erase(cache_topic_type_it);
cache_topic_it->second.erase(cache_topic_type_it);
}
// If the topic does not have any TopicData entries, erase the topic from the map.
if (cache_topic_it->second.empty()) {
Expand Down Expand Up @@ -770,7 +770,7 @@ rmw_ret_t fill_names_and_types(
});
// Fill topic names and types.
std::size_t index = 0;
for (const std::pair<std::string, GraphNode::TopicTypeMap> & item : entity_map) {
for (const std::pair<const std::string, GraphNode::TopicTypeMap> & item : entity_map) {
names_and_types->names.data[index] = rcutils_strdup(item.first.c_str(), *allocator);
if (!names_and_types->names.data[index]) {
return RMW_RET_BAD_ALLOC;
Expand Down
2 changes: 1 addition & 1 deletion rmw_zenoh_cpp/src/detail/graph_cache.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ struct GraphNode
// Map topic name to TopicTypeMap
// This uses a map that remembers insertion order because some parts of the client libraries
// expect that these are returned in the order that they were created.
using TopicMap = tsl::ordered_map<std::string, TopicTypeMap>;
using TopicMap = std::map<std::string, TopicTypeMap>;

// Entries for pub/sub.
TopicMap pubs_ = {};
Expand Down