Skip to content

Commit

Permalink
Use an ordered_map to store the TopicMap.
Browse files Browse the repository at this point in the history
Some of the tests in ROS 2 assume that the order in which
entities (pub, sub, clients, services) are added to the system
is the same order in which they will be returned from
calls like get_topic_names_and_types().  To facilitate that,
use an ordered_map for the mapping between a topic name and
the topic type, which remembers insertion order.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Jul 25, 2024
1 parent fcfed30 commit 27a010d
Show file tree
Hide file tree
Showing 6 changed files with 2,735 additions and 18 deletions.
15 changes: 13 additions & 2 deletions rmw_zenoh_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -84,8 +84,19 @@ register_rmw_implementation(
"cpp:rosidl_typesupport_cpp:rosidl_typesupport_fastrtps_cpp:rosidl_typesupport_introspection_cpp")

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
find_package(ament_cmake_copyright REQUIRED)
find_package(ament_cmake_cpplint REQUIRED)
find_package(ament_cmake_lint_cmake REQUIRED)
find_package(ament_cmake_uncrustify REQUIRED)
find_package(ament_cmake_xmllint REQUIRED)

set(_linter_excludes src/detail/ordered_hash.hpp src/detail/ordered_map.hpp)

ament_copyright()
ament_cpplint(EXCLUDE ${_linter_excludes})
ament_lint_cmake()
ament_uncrustify(EXCLUDE ${_linter_excludes})
ament_xmllint()
endif()

install(
Expand Down
2 changes: 2 additions & 0 deletions rmw_zenoh_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,9 @@
<version>0.0.1</version>
<description>A ROS 2 middleware implementation using zenoh-c</description>
<maintainer email="[email protected]">Yadunund</maintainer>

<license>Apache License 2.0</license>
<license>MIT</license> <!-- for ordered_{map,hash}.hpp -->

<author email="[email protected]">Chris Lalancette</author>
<author>Franco Cipollone</author>
Expand Down
30 changes: 15 additions & 15 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->second.find(
GraphNode::TopicTypeMap::iterator topic_type_map_it = topic_map_it.value().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->second.insert(
topic_map_it.value().insert(
std::make_pair(
graph_topic_data->info_.type_,
std::move(topic_qos_map)));
Expand Down Expand Up @@ -462,7 +462,7 @@ void GraphCache::update_topic_map_for_del(
}

GraphNode::TopicTypeMap::iterator cache_topic_type_it =
cache_topic_it->second.find(topic_info.type_);
cache_topic_it.value().find(topic_info.type_);
if (cache_topic_type_it == cache_topic_it->second.end()) {
// This should not happen.
RMW_ZENOH_LOG_ERROR_NAMED(
Expand Down Expand Up @@ -503,7 +503,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->second.erase(cache_topic_type_it);
cache_topic_it.value().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 @@ -782,21 +782,21 @@ rmw_ret_t fill_names_and_types(
});
// Fill topic names and types.
std::size_t index = 0;
for (const std::pair<const std::string, GraphNode::TopicTypeMap> & item : entity_map) {
for (const std::pair<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;
}
{
rcutils_ret_t rcutils_ret = rcutils_string_array_init(
&names_and_types->types[index],
item.second.size(),
allocator);
if (RCUTILS_RET_OK != rcutils_ret) {
RMW_SET_ERROR_MSG(rcutils_get_error_string().str);
return RMW_RET_BAD_ALLOC;
}

rcutils_ret_t rcutils_ret = rcutils_string_array_init(
&names_and_types->types[index],
item.second.size(),
allocator);
if (RCUTILS_RET_OK != rcutils_ret) {
RMW_SET_ERROR_MSG(rcutils_get_error_string().str);
return RMW_RET_BAD_ALLOC;
}

size_t type_index = 0;
for (const std::pair<const std::string, GraphNode::TopicQoSMap> & type : item.second) {
char * type_name = rcutils_strdup(_demangle_if_ros_type(type.first).c_str(), *allocator);
Expand Down Expand Up @@ -1208,7 +1208,7 @@ rmw_ret_t GraphCache::service_server_is_available(
std::lock_guard<std::mutex> lock(graph_mutex_);
GraphNode::TopicMap::iterator service_it = graph_services_.find(service_name);
if (service_it != graph_services_.end()) {
GraphNode::TopicTypeMap::iterator type_it = service_it->second.find(service_type);
GraphNode::TopicTypeMap::iterator type_it = service_it.value().find(service_type);
if (type_it != service_it->second.end()) {
for (const auto & [_, topic_data] : type_it->second) {
if (topic_data->subs_.size() > 0) {
Expand Down
3 changes: 2 additions & 1 deletion rmw_zenoh_cpp/src/detail/graph_cache.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@

#include "event.hpp"
#include "liveliness_utils.hpp"
#include "ordered_map.hpp"

#include "rcutils/allocator.h"
#include "rcutils/types.h"
Expand Down Expand Up @@ -80,7 +81,7 @@ struct GraphNode
// Map topic type to QoSMap
using TopicTypeMap = std::unordered_map<std::string, TopicQoSMap>;
// Map topic name to TopicTypeMap
using TopicMap = std::unordered_map<std::string, TopicTypeMap>;
using TopicMap = tsl::ordered_map<std::string, TopicTypeMap>;

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

0 comments on commit 27a010d

Please sign in to comment.