Skip to content

Commit

Permalink
Add simple console logger
Browse files Browse the repository at this point in the history
Signed-off-by: Yadunund <[email protected]>
  • Loading branch information
Yadunund committed Jun 29, 2024
1 parent d7243c0 commit 85ab442
Show file tree
Hide file tree
Showing 14 changed files with 271 additions and 66 deletions.
4 changes: 3 additions & 1 deletion .github/workflows/style.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -21,4 +21,6 @@ jobs:
- name: uncrustify
run: /ros_entrypoint.sh ament_uncrustify rmw_zenoh_cpp/
- name: cpplint
run: /ros_entrypoint.sh ament_cpplint rmw_zenoh_cpp/
# Ignore logging.hpp since the fmt::sprintf gets incorrectly flagged by ament_cpplint
# as a runtime/printf error.
run: /ros_entrypoint.sh ament_cpplint rmw_zenoh_cpp/ --exclude rmw_zenoh_cpp/src/detail/logging.hpp
6 changes: 5 additions & 1 deletion rmw_zenoh_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ find_package(ament_cmake REQUIRED)

find_package(ament_index_cpp REQUIRED)
find_package(fastcdr CONFIG REQUIRED)
find_package(fmt CONFIG REQUIRED)
find_package(rcpputils REQUIRED)
find_package(rcutils REQUIRED)
find_package(rosidl_typesupport_fastrtps_c REQUIRED)
Expand All @@ -36,6 +37,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 All @@ -59,6 +61,7 @@ target_link_libraries(rmw_zenoh_cpp
PRIVATE
ament_index_cpp::ament_index_cpp
fastcdr
fmt::fmt
rcpputils::rcpputils
rcutils::rcutils
rosidl_typesupport_fastrtps_c::rosidl_typesupport_fastrtps_c
Expand Down Expand Up @@ -105,12 +108,13 @@ 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
PRIVATE
ament_index_cpp::ament_index_cpp
rcutils::rcutils
fmt::fmt
rcpputils::rcpputils
rmw::rmw
zenohc::lib
Expand Down
1 change: 1 addition & 0 deletions rmw_zenoh_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

<depend>ament_index_cpp</depend>
<depend>fastcdr</depend>
<depend>fmt</depend>
<depend>rcpputils</depend>
<depend>rcutils</depend>
<depend>rosidl_typesupport_fastrtps_c</depend>
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
72 changes: 72 additions & 0 deletions rmw_zenoh_cpp/src/detail/logging.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
// 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(RMW_ZENOH_LOG_LEVEL_INFO);
return logger;
}

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

///=============================================================================
fmt::color Logger::level_to_color(LogLevel level) const
{
switch (level) {
case RMW_ZENOH_LOG_LEVEL_DEBUG:
return fmt::color::light_green;
case RMW_ZENOH_LOG_LEVEL_ERROR:
return fmt::color::indian_red;
case RMW_ZENOH_LOG_LEVEL_INFO:
return fmt::color::light_blue;
case RMW_ZENOH_LOG_LEVEL_WARN:
return fmt::color::light_yellow;
default:
return fmt::color::white;
}
}

///=============================================================================
std::string Logger::level_to_string(LogLevel level) const
{
switch (level) {
case RMW_ZENOH_LOG_LEVEL_DEBUG:
return "DEBUG";
case RMW_ZENOH_LOG_LEVEL_ERROR:
return "ERROR";
case RMW_ZENOH_LOG_LEVEL_INFO:
return "INFO";
case RMW_ZENOH_LOG_LEVEL_WARN:
return "WARN";
default:
return "UNKOWN";
}
}

///=============================================================================
void Logger::set_log_level(LogLevel new_level)
{
threshold_level_ = new_level;
}
} // namespace rmw_zenoh_cpp
Loading

0 comments on commit 85ab442

Please sign in to comment.