diff --git a/rmw_zenoh_cpp/src/detail/graph_cache.cpp b/rmw_zenoh_cpp/src/detail/graph_cache.cpp index b22a1544..53b23182 100644 --- a/rmw_zenoh_cpp/src/detail/graph_cache.cpp +++ b/rmw_zenoh_cpp/src/detail/graph_cache.cpp @@ -76,7 +76,7 @@ void GraphCache::parse_put(const std::string & keyexpr) entity.type() != EntityType::Service && entity.type() != EntityType::Client) { - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "add_topic_data() for invalid EntityType. Report this."); return; @@ -85,7 +85,7 @@ void GraphCache::parse_put(const std::string & keyexpr) if (!entity.topic_info().has_value()) { // This should not happen as add_topic_data() is called after validating the existence // of topic_info. - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "add_topic_data() called without valid TopicInfo. Report this."); return; @@ -173,7 +173,7 @@ void GraphCache::parse_put(const std::string & keyexpr) } } - RCUTILS_LOG_INFO_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "Added %s on topic %s with type %s to node /%s.", entity_desc.c_str(), @@ -212,7 +212,7 @@ void GraphCache::parse_put(const std::string & keyexpr) NodeMap node_map = { {entity.node_name(), make_graph_node(entity)}}; graph_.emplace(std::make_pair(entity.node_namespace(), std::move(node_map))); - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "Added node /%s to a new namespace %s in the graph.", entity.node_name().c_str(), entity.node_namespace().c_str()); @@ -238,7 +238,7 @@ void GraphCache::parse_put(const std::string & keyexpr) NodeMap::iterator insertion_it = ns_it->second.insert(std::make_pair(entity.node_name(), make_graph_node(entity))); if (insertion_it != ns_it->second.end()) { - RCUTILS_LOG_INFO_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "Added a new node /%s with id %s to an existing namespace %s in the graph.", entity.node_name().c_str(), @@ -332,7 +332,7 @@ void GraphCache::parse_del(const std::string & keyexpr) entity.type() != EntityType::Service && entity.type() != EntityType::Client) { - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "remove_topic_data() for invalid EntityType. Report this."); return; @@ -341,7 +341,7 @@ void GraphCache::parse_del(const std::string & keyexpr) if (!entity.topic_info().has_value()) { // This should not happen as add_topic_data() is called after validating the existence // of topic_info. - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "remove_topic_data() called without valid TopicInfo. Report this."); return; @@ -407,7 +407,7 @@ void GraphCache::parse_del(const std::string & keyexpr) // Bookkeeping: Update graph_topic_ which keeps track of topics across all nodes in the graph. update_graph_topics(topic_info, entity.type(), pub_count, sub_count); - RCUTILS_LOG_INFO_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "Removed %s on topic %s with type %s to node /%s.", entity_desc.c_str(), @@ -437,7 +437,7 @@ void GraphCache::parse_del(const std::string & keyexpr) }); if (node_it == range.second) { // Node does not exist. - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "Received liveliness token to remove unknown node /%s from the graph. Ignoring...", entity.node_name().c_str() @@ -452,7 +452,7 @@ void GraphCache::parse_del(const std::string & keyexpr) // the node below, we should update the count in graph_topics_. const GraphNodePtr graph_node = node_it->second; if (!graph_node->pubs_.empty() || !graph_node->subs_.empty()) { - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "Received liveliness token to remove node /%s from the graph before all pub/subs for this " "node have been removed. Removing all pub/subs first...", @@ -477,7 +477,7 @@ void GraphCache::parse_del(const std::string & keyexpr) remove_topics(graph_node->clients_, EntityType::Client); } ns_it->second.erase(node_it); - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "Removed node /%s from the graph.", entity.node_name().c_str() diff --git a/rmw_zenoh_cpp/src/rmw_init.cpp b/rmw_zenoh_cpp/src/rmw_init.cpp index 1b612d88..f0458b63 100644 --- a/rmw_zenoh_cpp/src/rmw_init.cpp +++ b/rmw_zenoh_cpp/src/rmw_init.cpp @@ -46,7 +46,7 @@ static void graph_sub_data_handler( { (void)data; z_owned_str_t keystr = z_keyexpr_to_string(sample->keyexpr); - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "[graph_sub_data_handler] Received key '%s'", z_loan(keystr) @@ -56,7 +56,7 @@ static void graph_sub_data_handler( rmw_context_impl_s * context_impl = static_cast( data); if (context_impl == nullptr) { - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "[graph_sub_data_handler] Unable to convert data into context_impl" ); @@ -250,7 +250,7 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) const std::string liveliness_str = liveliness::subscription_token(context->actual_domain_id); // Query router/liveliness participants to get graph information before this session was started. - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "Sending Query '%s' to fetch discovery data...", liveliness_str.c_str() @@ -275,9 +275,9 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) if (z_reply_is_ok(&reply)) { z_sample_t sample = z_reply_ok(&reply); z_owned_str_t keystr = z_keyexpr_to_string(sample.keyexpr); - printf( - ">> [discovery] Received ('%s': '%.*s')\n", z_loan(keystr), - static_cast(sample.payload.len), sample.payload.start); + // printf( + // ">> [discovery] Received ('%s': '%.*s')\n", z_loan(keystr), + // static_cast(sample.payload.len), sample.payload.start); context->impl->graph_cache.parse_put(z_loan(keystr)); z_drop(z_move(keystr)); } else { @@ -288,7 +288,7 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) z_drop(z_move(channel)); // TODO(Yadunund): Switch this to a liveliness subscriptions once the API is available. - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "Setting up liveliness subscription on key: %s", liveliness_str.c_str() diff --git a/rmw_zenoh_cpp/src/rmw_zenoh.cpp b/rmw_zenoh_cpp/src/rmw_zenoh.cpp index 87c5840c..03c8d0dc 100644 --- a/rmw_zenoh_cpp/src/rmw_zenoh.cpp +++ b/rmw_zenoh_cpp/src/rmw_zenoh.cpp @@ -3023,7 +3023,7 @@ rmw_wait( return RMW_RET_INCORRECT_RMW_IMPLEMENTATION); // TODO(yadunund): Switch to debug log level. - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "[rmw_wait] %ld subscriptions, %ld services, %ld clients, %ld events, %ld guard conditions", subscriptions->subscriber_count, @@ -3034,7 +3034,7 @@ rmw_wait( // TODO(yadunund): Switch to debug log level. if (wait_timeout) { - RCUTILS_LOG_WARN_NAMED( + RCUTILS_LOG_DEBUG_NAMED( "rmw_zenoh_common_cpp", "[rmw_wait] TIMEOUT: %ld s %ld ns", wait_timeout->sec, wait_timeout->nsec);