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

Switch to custom logging macros to avoid deadlocks #223

Merged
merged 5 commits into from
Jul 1, 2024
Merged
Show file tree
Hide file tree
Changes from 2 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
2 changes: 2 additions & 0 deletions rmw_zenoh_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ add_library(rmw_zenoh_cpp SHARED
src/detail/graph_cache.cpp
src/detail/guard_condition.cpp
src/detail/liveliness_utils.cpp
src/detail/logging.cpp
src/detail/message_type_support.cpp
src/detail/rmw_data_types.cpp
src/detail/service_type_support.cpp
Expand Down Expand Up @@ -105,6 +106,7 @@ add_executable(rmw_zenohd
src/zenohd/main.cpp
src/detail/zenoh_config.cpp
src/detail/liveliness_utils.cpp
src/detail/logging.cpp
)

target_link_libraries(rmw_zenohd
Expand Down
4 changes: 2 additions & 2 deletions rmw_zenoh_cpp/src/detail/event.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include "event.hpp"

#include "rcutils/logging_macros.h"
#include "logging_macros.hpp"

#include "rmw/error_handling.h"

Expand Down Expand Up @@ -148,7 +148,7 @@ void EventsManager::add_new_event(
std::deque<std::unique_ptr<rmw_zenoh_event_status_t>> & event_queue = event_queues_[event_id];
if (event_queue.size() >= event_queue_depth_) {
// Log warning if message is discarded due to hitting the queue depth
RCUTILS_LOG_DEBUG_NAMED(
RMW_ZENOH_LOG_DEBUG_NAMED(
"rmw_zenoh_cpp",
"Event queue depth of %ld reached, discarding oldest message "
"for event type %d",
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 @@ -25,7 +25,6 @@
#include "rcpputils/find_and_replace.hpp"
#include "rcpputils/scope_exit.hpp"

#include "rcutils/logging_macros.h"
#include "rcutils/strdup.h"

#include "rmw/error_handling.h"
Expand All @@ -36,6 +35,7 @@
#include "rosidl_runtime_c/type_hash.h"

#include "graph_cache.hpp"
#include "logging_macros.hpp"
#include "rmw_data_types.hpp"

namespace rmw_zenoh_cpp
Expand Down Expand Up @@ -131,7 +131,7 @@ void GraphCache::update_topic_map_for_put(
TopicDataPtr graph_topic_data = TopicData::make(entity);
if (graph_topic_data == nullptr) {
// This should not happen as topic_info should be populated for all non-node entities.
RCUTILS_LOG_WARN_NAMED(
RMW_ZENOH_LOG_WARN_NAMED(
"rmw_zenoh_cpp",
"update_topic_map_for_put() called for non-node entity without valid TopicInfo. "
"Report this.");
Expand Down Expand Up @@ -339,7 +339,7 @@ void GraphCache::parse_put(
return;
}
if (ignore_from_current_session && is_entity_local(*entity)) {
RCUTILS_LOG_DEBUG_NAMED(
RMW_ZENOH_LOG_DEBUG_NAMED(
"rmw_zenoh_cpp",
"Ignoring parse_put for %s from the same session.\n", entity->keyexpr().c_str());
return;
Expand Down Expand Up @@ -391,7 +391,7 @@ void GraphCache::parse_put(
update_topic_maps_for_put(node, entity);
total_nodes_in_graph_ += 1;
if (insertion_it == ns_it->second.end()) {
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Unable to add a new node /%s to an "
"existing namespace %s in the graph. Report this bug.",
Expand Down Expand Up @@ -442,7 +442,7 @@ void GraphCache::update_topic_map_for_del(
bool report_events)
{
if (!entity->topic_info().has_value()) {
RCUTILS_LOG_WARN_NAMED(
RMW_ZENOH_LOG_WARN_NAMED(
"rmw_zenoh_cpp",
"update_topic_maps_for_del() called for non-node entity without valid TopicInfo. "
"Report this.");
Expand All @@ -455,7 +455,7 @@ void GraphCache::update_topic_map_for_del(
topic_map.find(topic_info.name_);
if (cache_topic_it == topic_map.end()) {
// This should not happen.
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp", "topic name %s not found in topic_map. Report this.",
topic_info.name_.c_str());
return;
Expand All @@ -465,7 +465,7 @@ void GraphCache::update_topic_map_for_del(
cache_topic_it->second.find(topic_info.type_);
if (cache_topic_type_it == cache_topic_it->second.end()) {
// This should not happen.
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp", "topic type %s not found in for topic %s. Report this.",
topic_info.type_.c_str(), topic_info.name_.c_str());
return;
Expand All @@ -476,7 +476,7 @@ void GraphCache::update_topic_map_for_del(
qos_str);
if (cache_topic_qos_it == cache_topic_type_it->second.end()) {
// This should not happen.
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp", "qos %s not found in for topic type %s. Report this.",
qos_str.c_str(), topic_info.type_.c_str());
return;
Expand Down Expand Up @@ -557,7 +557,7 @@ void GraphCache::parse_del(
return;
}
if (ignore_from_current_session && is_entity_local(*entity)) {
RCUTILS_LOG_DEBUG_NAMED(
RMW_ZENOH_LOG_DEBUG_NAMED(
"rmw_zenoh_cpp",
"Ignoring parse_del for %s from the same session.\n", entity->keyexpr().c_str());
return;
Expand All @@ -583,7 +583,7 @@ void GraphCache::parse_del(
});
if (node_it == range.second) {
// Node does not exist.
RCUTILS_LOG_WARN_NAMED(
RMW_ZENOH_LOG_WARN_NAMED(
"rmw_zenoh_cpp",
"Received liveliness token to remove unknown node /%s from the graph. Ignoring...",
entity->node_name().c_str()
Expand All @@ -602,7 +602,7 @@ void GraphCache::parse_del(
!graph_node->clients_.empty() ||
!graph_node->services_.empty())
{
RCUTILS_LOG_WARN_NAMED(
RMW_ZENOH_LOG_WARN_NAMED(
"rmw_zenoh_cpp",
"Received liveliness token to remove node /%s from the graph before all pub/subs/"
"clients/services for this node have been removed. Removing all entities first...",
Expand Down Expand Up @@ -658,7 +658,7 @@ rmw_ret_t GraphCache::get_node_names(
[node_names]() {
rcutils_ret_t ret = rcutils_string_array_fini(node_names);
if (ret != RCUTILS_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"failed to cleanup during error handling: %s", rcutils_get_error_string().str);
}
Expand All @@ -673,7 +673,7 @@ rmw_ret_t GraphCache::get_node_names(
[node_namespaces]() {
rcutils_ret_t ret = rcutils_string_array_fini(node_namespaces);
if (ret != RCUTILS_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"failed to cleanup during error handling: %s", rcutils_get_error_string().str);
}
Expand All @@ -682,7 +682,7 @@ rmw_ret_t GraphCache::get_node_names(
auto free_enclaves_lambda = [enclaves]() -> void {
rcutils_ret_t ret = rcutils_string_array_fini(enclaves);
if (ret != RCUTILS_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"failed to cleanup during error handling: %s", rcutils_get_error_string().str);
}
Expand Down Expand Up @@ -1231,7 +1231,7 @@ void GraphCache::set_qos_event_callback(
std::lock_guard<std::mutex> lock(graph_mutex_);

if (event_type > ZENOH_EVENT_ID_MAX) {
RCUTILS_LOG_WARN_NAMED(
RMW_ZENOH_LOG_WARN_NAMED(
"rmw_zenoh_cpp",
"set_qos_event_callback() called for unsupported event. Report this.");
return;
Expand Down
15 changes: 8 additions & 7 deletions rmw_zenoh_cpp/src/detail/liveliness_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,9 @@
#include <utility>
#include <vector>

#include "logging_macros.hpp"

#include "rcpputils/scope_exit.hpp"
#include "rcutils/logging_macros.h"

#include "rmw/error_handling.h"

Expand Down Expand Up @@ -411,7 +412,7 @@ std::shared_ptr<Entity> Entity::make(const std::string & keyexpr)
// (ADMIN_SPACE, domain_id, zid, id, entity_type, namespace, node_name).
// Basic validation.
if (parts.size() < KEYEXPR_INDEX_MIN + 1) {
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Received invalid liveliness token with %lu/%d parts: %s",
parts.size(),
Expand All @@ -420,15 +421,15 @@ std::shared_ptr<Entity> Entity::make(const std::string & keyexpr)
}
for (const std::string & p : parts) {
if (p.empty()) {
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Received invalid liveliness token with empty parts: %s", keyexpr.c_str());
return nullptr;
}
}

if (parts[KeyexprIndex::AdminSpace] != ADMIN_SPACE) {
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Received liveliness token with invalid admin space.");
return nullptr;
Expand All @@ -439,7 +440,7 @@ std::shared_ptr<Entity> Entity::make(const std::string & keyexpr)
std::unordered_map<std::string, EntityType>::const_iterator entity_it =
str_to_entity.find(entity_str);
if (entity_it == str_to_entity.end()) {
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Received liveliness token with invalid entity %s.", entity_str.c_str());
return nullptr;
Expand All @@ -458,14 +459,14 @@ std::shared_ptr<Entity> Entity::make(const std::string & keyexpr)
// Populate topic_info if we have a token for an entity other than a node.
if (entity_type != EntityType::Node) {
if (parts.size() < KEYEXPR_INDEX_MAX + 1) {
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Received liveliness token for non-node entity without required parameters.");
return nullptr;
}
std::optional<rmw_qos_profile_t> qos = keyexpr_to_qos(parts[KeyexprIndex::TopicQoS]);
if (!qos.has_value()) {
RCUTILS_LOG_ERROR_NAMED(
RMW_ZENOH_LOG_ERROR_NAMED(
"rmw_zenoh_cpp",
"Received liveliness token with invalid qos keyexpr");
return nullptr;
Expand Down
38 changes: 38 additions & 0 deletions rmw_zenoh_cpp/src/detail/logging.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "logging.hpp"

#include <sstream>

namespace rmw_zenoh_cpp
{
///=============================================================================
Logger & Logger::get()
{
static Logger logger(RCUTILS_LOG_SEVERITY_INFO);
return logger;
}

///=============================================================================
Logger::Logger(RCUTILS_LOG_SEVERITY threshold_level)
: threshold_level_(threshold_level)
{}

///=============================================================================
void Logger::set_log_level(RCUTILS_LOG_SEVERITY new_level)
{
threshold_level_ = new_level;
}
} // namespace rmw_zenoh_cpp
71 changes: 71 additions & 0 deletions rmw_zenoh_cpp/src/detail/logging.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DETAIL__LOGGING_HPP_
#define DETAIL__LOGGING_HPP_

#include <rcutils/logging.h>

#include <iostream>
#include <mutex>
#include <string>
#include <sstream>

namespace rmw_zenoh_cpp
{
///=============================================================================
class Logger
{
public:
// Get a static reference to the logger.
static Logger & get();

// Set the threshold log level.
void set_log_level(RCUTILS_LOG_SEVERITY new_level);

// Log to the console.
void log_named(
RCUTILS_LOG_SEVERITY level,
const char * name,
const char * message,
...) const
{
if (level >= threshold_level_) {
rcutils_time_point_value_t now;
rcutils_ret_t ret = rcutils_system_time_now(&now);
if (ret != RCUTILS_RET_OK) {
RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to get timestamp while doing a console logging.\n");
return;
}
static rcutils_log_location_t log_location = {__func__, __FILE__, __LINE__};
va_list args;
va_start(args, message);
rcutils_logging_console_output_handler(
&log_location,
level,
name,
now,
message,
&args
);
}
}
Yadunund marked this conversation as resolved.
Show resolved Hide resolved

private:
RCUTILS_LOG_SEVERITY threshold_level_;
explicit Logger(RCUTILS_LOG_SEVERITY threshold_level);
};
} // namespace rmw_zenoh_cpp

#endif // DETAIL__LOGGING_HPP_
37 changes: 37 additions & 0 deletions rmw_zenoh_cpp/src/detail/logging_macros.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DETAIL__LOGGING_MACROS_HPP_
#define DETAIL__LOGGING_MACROS_HPP_

#include "logging.hpp"

///=============================================================================
// We define custom logging marcos to log to console as it was discovered
// that relying on RCUTILS_LOG_X_NAMED functions also end up logging over /rosout
// which can lead to deadlocks in rmw_zenoh especially when multiple threads
// invoke GraphCache::parse_put() and GraphCache::parse_del() functions.
// See https://github.com/ros2/rmw_zenoh/issues/182 for more details.
// Note: Consider adding a set_rmw_log_level() API to rmw which can override the
// default log level at the RMW layer.
Yadunund marked this conversation as resolved.
Show resolved Hide resolved
#define RMW_ZENOH_LOG_DEBUG_NAMED(...) {rmw_zenoh_cpp::Logger::get().log_named( \
RCUTILS_LOG_SEVERITY_DEBUG, __VA_ARGS__);}
#define RMW_ZENOH_LOG_ERROR_NAMED(...) {rmw_zenoh_cpp::Logger::get().log_named( \
RCUTILS_LOG_SEVERITY_ERROR, __VA_ARGS__);}
#define RMW_ZENOH_LOG_INFO_NAMED(...) {rmw_zenoh_cpp::Logger::get().log_named( \
RCUTILS_LOG_SEVERITY_INFO, __VA_ARGS__);}
#define RMW_ZENOH_LOG_WARN_NAMED(...) {rmw_zenoh_cpp::Logger::get().log_named( \
RCUTILS_LOG_SEVERITY_WARN, __VA_ARGS__);}

#endif // DETAIL__LOGGING_MACROS_HPP_
Loading