diff --git a/.github/workflows/style.yaml b/.github/workflows/style.yaml
index fb5bd053..ff88958f 100644
--- a/.github/workflows/style.yaml
+++ b/.github/workflows/style.yaml
@@ -21,6 +21,4 @@ jobs:
- name: uncrustify
run: /ros_entrypoint.sh ament_uncrustify rmw_zenoh_cpp/
- name: cpplint
- # 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
+ run: /ros_entrypoint.sh ament_cpplint rmw_zenoh_cpp/
diff --git a/rmw_zenoh_cpp/CMakeLists.txt b/rmw_zenoh_cpp/CMakeLists.txt
index 8b72873d..a67c7c6f 100644
--- a/rmw_zenoh_cpp/CMakeLists.txt
+++ b/rmw_zenoh_cpp/CMakeLists.txt
@@ -16,7 +16,6 @@ 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)
@@ -61,7 +60,6 @@ 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
@@ -114,7 +112,7 @@ add_executable(rmw_zenohd
target_link_libraries(rmw_zenohd
PRIVATE
ament_index_cpp::ament_index_cpp
- fmt::fmt
+ rcutils::rcutils
rcpputils::rcpputils
rmw::rmw
zenohc::lib
diff --git a/rmw_zenoh_cpp/package.xml b/rmw_zenoh_cpp/package.xml
index 72ea95c8..6304ab32 100644
--- a/rmw_zenoh_cpp/package.xml
+++ b/rmw_zenoh_cpp/package.xml
@@ -14,7 +14,6 @@
ament_index_cpp
fastcdr
- fmt
rcpputils
rcutils
rosidl_typesupport_fastrtps_c
diff --git a/rmw_zenoh_cpp/src/detail/logging.cpp b/rmw_zenoh_cpp/src/detail/logging.cpp
index 2e845da1..a54bda18 100644
--- a/rmw_zenoh_cpp/src/detail/logging.cpp
+++ b/rmw_zenoh_cpp/src/detail/logging.cpp
@@ -21,51 +21,17 @@ namespace rmw_zenoh_cpp
///=============================================================================
Logger & Logger::get()
{
- static Logger logger(RMW_ZENOH_LOG_LEVEL_INFO);
+ static Logger logger(RCUTILS_LOG_SEVERITY_INFO);
return logger;
}
///=============================================================================
-Logger::Logger(LogLevel threshold_level)
+Logger::Logger(RCUTILS_LOG_SEVERITY 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)
+void Logger::set_log_level(RCUTILS_LOG_SEVERITY new_level)
{
threshold_level_ = new_level;
}
diff --git a/rmw_zenoh_cpp/src/detail/logging.hpp b/rmw_zenoh_cpp/src/detail/logging.hpp
index 7e7083f2..70cb2ab5 100644
--- a/rmw_zenoh_cpp/src/detail/logging.hpp
+++ b/rmw_zenoh_cpp/src/detail/logging.hpp
@@ -15,9 +15,7 @@
#ifndef DETAIL__LOGGING_HPP_
#define DETAIL__LOGGING_HPP_
-#include
-#include
-#include
+#include
#include
#include
@@ -26,15 +24,6 @@
namespace rmw_zenoh_cpp
{
-///=============================================================================
-enum LogLevel
-{
- RMW_ZENOH_LOG_LEVEL_DEBUG,
- RMW_ZENOH_LOG_LEVEL_INFO,
- RMW_ZENOH_LOG_LEVEL_WARN,
- RMW_ZENOH_LOG_LEVEL_ERROR,
-};
-
///=============================================================================
class Logger
{
@@ -43,42 +32,40 @@ class Logger
static Logger & get();
// Set the threshold log level.
- void set_log_level(LogLevel new_level);
+ void set_log_level(RCUTILS_LOG_SEVERITY new_level);
// Log to the console.
- template
void log_named(
- LogLevel level,
- const std::string & name,
- const std::string & message,
- const Args &... args) const
+ RCUTILS_LOG_SEVERITY level,
+ const char * name,
+ const char * message,
+ ...) const
{
if (level >= threshold_level_) {
- const auto time_now = std::chrono::system_clock::now().time_since_epoch();
- const auto seconds =
- std::chrono::duration_cast(time_now).count();
- auto nanoseconds =
- std::chrono::duration_cast(
- time_now - std::chrono::seconds(seconds)).count();
- fmt::print(
- fmt::fg(level_to_color(level)),
- "[{}] [{}.{}] [{}]: {}\n",
- level_to_string(level),
- seconds,
- nanoseconds,
+ 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,
- fmt::sprintf(message, args ...)
+ now,
+ message,
+ &args
);
}
}
private:
- LogLevel threshold_level_;
- explicit Logger(LogLevel threshold_level);
- fmt::color level_to_color(LogLevel level) const;
- std::string level_to_string(LogLevel level) const;
+ RCUTILS_LOG_SEVERITY threshold_level_;
+ explicit Logger(RCUTILS_LOG_SEVERITY threshold_level);
};
-
} // namespace rmw_zenoh_cpp
#endif // DETAIL__LOGGING_HPP_
diff --git a/rmw_zenoh_cpp/src/detail/logging_macros.hpp b/rmw_zenoh_cpp/src/detail/logging_macros.hpp
index 58a3e5e9..89f0184c 100644
--- a/rmw_zenoh_cpp/src/detail/logging_macros.hpp
+++ b/rmw_zenoh_cpp/src/detail/logging_macros.hpp
@@ -26,12 +26,12 @@
// Note: Consider adding a set_rmw_log_level() API to rmw which can override the
// default log level at the RMW layer.
#define RMW_ZENOH_LOG_DEBUG_NAMED(...) {rmw_zenoh_cpp::Logger::get().log_named( \
- rmw_zenoh_cpp::RMW_ZENOH_LOG_LEVEL_DEBUG, __VA_ARGS__);}
+ RCUTILS_LOG_SEVERITY_DEBUG, __VA_ARGS__);}
#define RMW_ZENOH_LOG_ERROR_NAMED(...) {rmw_zenoh_cpp::Logger::get().log_named( \
- rmw_zenoh_cpp::RMW_ZENOH_LOG_LEVEL_ERROR, __VA_ARGS__);}
+ RCUTILS_LOG_SEVERITY_ERROR, __VA_ARGS__);}
#define RMW_ZENOH_LOG_INFO_NAMED(...) {rmw_zenoh_cpp::Logger::get().log_named( \
- rmw_zenoh_cpp::RMW_ZENOH_LOG_LEVEL_INFO, __VA_ARGS__);}
+ RCUTILS_LOG_SEVERITY_INFO, __VA_ARGS__);}
#define RMW_ZENOH_LOG_WARN_NAMED(...) {rmw_zenoh_cpp::Logger::get().log_named( \
- rmw_zenoh_cpp::RMW_ZENOH_LOG_LEVEL_WARN, __VA_ARGS__);}
+ RCUTILS_LOG_SEVERITY_WARN, __VA_ARGS__);}
#endif // DETAIL__LOGGING_MACROS_HPP_
diff --git a/rmw_zenoh_cpp/src/detail/rmw_data_types.cpp b/rmw_zenoh_cpp/src/detail/rmw_data_types.cpp
index 87d20fc8..ea0dac4a 100644
--- a/rmw_zenoh_cpp/src/detail/rmw_data_types.cpp
+++ b/rmw_zenoh_cpp/src/detail/rmw_data_types.cpp
@@ -537,7 +537,7 @@ void client_data_handler(z_owned_reply_t * reply, void * data)
"z_reply_is_ok returned False for keyexpr %s. Reason: %.*s",
z_loan(keystr),
(int)err.payload.len,
- fmt::ptr(err.payload.start));
+ err.payload.start);
z_drop(z_move(keystr));
return;