Skip to content

Commit

Permalink
Style cleanups.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Nov 27, 2023
1 parent 6bc2f39 commit 7f6fa1f
Show file tree
Hide file tree
Showing 4 changed files with 36 additions and 30 deletions.
27 changes: 14 additions & 13 deletions rmw_zenoh_cpp/src/detail/graph_cache.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,14 +93,15 @@ void GraphCache::parse_put(const std::string & keyexpr)
graph_topic_data->info_.type_,
graph_topic_data));
if (!type_insertion.second) {
// We have another instance of a pub/sub over the same topic and type so we increment the counters.
// We have another instance of a pub/sub over the same topic and type so we increment
// the counters.
auto & existing_graph_topic = type_insertion.first->second;
existing_graph_topic->stats_.pub_count_ += pub_count;
existing_graph_topic->stats_.pub_count_ += sub_count;
}
}

// Bookkeeping: We update graph_topic_ which keeps track of topics across all nodes in the graph.
// Bookkeeping: Update graph_topic_ which keeps track of topics across all nodes in the graph.
if (update_cache) {
auto cache_topic_it = graph_topics_.find(entity.topic_info()->name_);
if (cache_topic_it == graph_topics_.end()) {
Expand All @@ -113,8 +114,8 @@ void GraphCache::parse_put(const std::string & keyexpr)
{entity.topic_info()->type_, topic_data_ptr}
};
} else {
// If a TopicData entry for the same type exists in the topic map, update pub/sub counts or
// else create an new TopicData.
// If a TopicData entry for the same type exists in the topic map, update pub/sub counts
// or else create an new TopicData.
auto topic_data_insertion =
cache_topic_it->second.insert(std::make_pair(entity.topic_info()->type_, nullptr));
if (topic_data_insertion.second) {
Expand Down Expand Up @@ -251,7 +252,7 @@ void GraphCache::parse_del(const std::string & keyexpr)
return;
}

// Decrement the relevant counters. Check if both counters are 0 and if so remove from graph_node.
// Decrement the relevant counters. If both counters are 0 remove from graph_node.
auto & existing_topic_data = topic_data_it->second;
existing_topic_data->stats_.pub_count_ -= pub_count;
existing_topic_data->stats_.sub_count_ -= sub_count;
Expand All @@ -265,7 +266,7 @@ void GraphCache::parse_del(const std::string & keyexpr)
topic_map.erase(entity.topic_info()->name_);
}

// Bookkeeping: We update graph_topic_ which keeps track of topics across all nodes in the graph.
// Bookkeeping: Update graph_topic_ which keeps track of topics across all nodes in the graph.
if (update_cache) {
auto cache_topic_it = graph_topics_.find(entity.topic_info()->name_);
if (cache_topic_it == graph_topics_.end()) {
Expand All @@ -276,7 +277,7 @@ void GraphCache::parse_del(const std::string & keyexpr)
} else {
auto cache_topic_data_it = cache_topic_it->second.find(entity.topic_info()->type_);
if (cache_topic_data_it != cache_topic_it->second.end()) {
// Decrement the relevant counters. Check if both counters are 0 and if so remove from cache.
// Decrement the relevant counters. If both counters are 0 remove from cache.
cache_topic_data_it->second->stats_.pub_count_ -= pub_count;
cache_topic_data_it->second->stats_.sub_count_ -= sub_count;
if (cache_topic_data_it->second->stats_.pub_count_ == 0 &&
Expand All @@ -289,7 +290,6 @@ void GraphCache::parse_del(const std::string & keyexpr)
graph_topics_.erase(cache_topic_it);
}
}

}
}

Expand Down Expand Up @@ -321,17 +321,18 @@ void GraphCache::parse_del(const std::string & keyexpr)
if (entity.type() == EntityType::Node) {
// Node
// The liveliness tokens to remove pub/subs should be received before the one to remove a node
// given the reliability QoS for liveliness subs. However, if we find any pubs/subs present in the node below,
// we should update the count in graph_topics_.
// given the reliability QoS for liveliness subs. However, if we find any pubs/subs present in
// the node below, we should update the count in graph_topics_.
const auto graph_node = node_it->second;
if (!graph_node->pubs_.empty() || !graph_node->subs_.empty()) {
RCUTILS_LOG_WARN_NAMED(
"rmw_zenoh_cpp",
"Received liveliness token to remove node /%s from the graph before all pub/subs for this node have been removed. "
"Report this issue.",
"Received liveliness token to remove node /%s from the graph before all pub/subs for this "
"node have been removed. Report this issue.",
entity.node_info().name_.c_str()
);
// TODO(Yadunund): Iterate through the nodes pubs_ and subs_ and decrement topic count in graph_topics_.
// TODO(Yadunund): Iterate through the nodes pubs_ and subs_ and decrement topic count in
// graph_topics_.
}
ns_it->second.erase(entity.node_info().name_);
RCUTILS_LOG_WARN_NAMED(
Expand Down
31 changes: 18 additions & 13 deletions rmw_zenoh_cpp/src/detail/liveliness_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,12 @@

#include "liveliness_utils.hpp"

#include <optional>
#include <sstream>
#include <stdexcept>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

#include "rcpputils/scope_exit.hpp"
Expand Down Expand Up @@ -55,12 +60,12 @@ namespace
{

/// The admin space used to prefix the liveliness tokens.
static const std::string ADMIN_SPACE = "@ros2_lv";
static const std::string NODE_STR = "NN";
static const std::string PUB_STR = "MP";
static const std::string SUB_STR = "MS";
static const std::string SRV_STR = "SS";
static const std::string CLI_STR = "SC";
static const char ADMIN_SPACE[] = "@ros2_lv";
static const char NODE_STR[] = "NN";
static const char PUB_STR[] = "MP";
static const char SUB_STR[] = "MS";
static const char SRV_STR[] = "SS";
static const char CLI_STR[] = "SC";

static const std::unordered_map<EntityType, std::string> entity_to_str = {
{EntityType::Node, NODE_STR},
Expand All @@ -78,12 +83,12 @@ static const std::unordered_map<std::string, EntityType> str_to_entity = {
{CLI_STR, EntityType::Client}
};

} // namespace
} // namespace

///=============================================================================
std::string subscription_token(size_t domain_id)
{
std::string token = ADMIN_SPACE + "/" + std::to_string(domain_id) + "/**";
std::string token = std::string(ADMIN_SPACE) + "/" + std::to_string(domain_id) + "/**";
return token;
}

Expand Down Expand Up @@ -156,7 +161,7 @@ std::optional<Entity> Entity::make(
}

Entity entity{std::move(type), std::move(node_info), std::move(topic_info)};
return std::move(entity);
return entity;
}

namespace
Expand Down Expand Up @@ -192,14 +197,14 @@ std::vector<std::string> split_keyexpr(
return result;
}

} // namespace
} // namespace

///=============================================================================
std::optional<Entity> Entity::make(const std::string & keyexpr)
{

std::vector<std::string> parts = split_keyexpr(keyexpr);
// At minimum, a token will contain 5 parts (ADMIN_SPACE, domain_id, entity_str, namespace, node_name).
// A token will contain at least 5 parts:
// (ADMIN_SPACE, domain_id, entity_str, namespace, node_name).
// Basic validation.
if (parts.size() < 5) {
RCUTILS_LOG_ERROR_NAMED(
Expand Down Expand Up @@ -344,4 +349,4 @@ bool PublishToken::del(
return true;
}

} // namespace liveliness
} // namespace liveliness
5 changes: 2 additions & 3 deletions rmw_zenoh_cpp/src/detail/liveliness_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <optional>
#include <string>
#include <unordered_map>
#include <vector>


namespace liveliness
Expand All @@ -28,7 +28,6 @@ namespace liveliness
///=============================================================================
struct NodeInfo
{

std::size_t domain_id_;
std::string ns_;
std::string name_;
Expand Down Expand Up @@ -126,6 +125,6 @@ class PublishToken
const std::string & token);
};

} // namespace liveliness
} // namespace liveliness

#endif // DETAIL__LIVELINESS_UTILS_HPP_
3 changes: 2 additions & 1 deletion rmw_zenoh_cpp/src/rmw_zenoh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -251,7 +251,8 @@ rmw_destroy_node(rmw_node_t * node)
// Publish to the graph that a node has ridden off into the sunset
// const bool del_result = PublishToken::del(
// &node->context->impl->session,
// liveliness::GenerateToken::node(node->context->actual_domain_id, node->namespace_, node->name)
// liveliness::GenerateToken::node(node->context->actual_domain_id, node->namespace_,
// node->name)
// );
// if (!del_result) {
// return RMW_RET_ERROR;
Expand Down

0 comments on commit 7f6fa1f

Please sign in to comment.