Skip to content

Commit

Permalink
Move spdlog::logger to gz-utils
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <mjcarroll@intrinsic.ai>
  • Loading branch information
mjcarroll committed Jul 31, 2024
1 parent b62b30a commit 965eff9
Show file tree
Hide file tree
Showing 9 changed files with 364 additions and 1 deletion.
4 changes: 3 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,13 @@ if(NOT GZ_UTILS_VENDOR_CLI11)
gz_find_package(CLI11 REQUIRED_BY cli PKGCONFIG_IGNORE)
endif()

gz_find_package(spdlog REQUIRED_BY logger)

#============================================================================
# Configure the build
#============================================================================
gz_configure_build(QUIT_IF_BUILD_ERRORS
COMPONENTS cli)
COMPONENTS cli logger)

#============================================================================
# Create package information
Expand Down
1 change: 1 addition & 0 deletions cli/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ gz_add_component(
cli
INTERFACE
INDEPENDENT_FROM_PROJECT_LIB
LIB_DEPS spdlog::spdlog
GET_TARGET_NAME gz_utils_cli_target_name)

# Make sure that the name is visible also in cli/include/CMakeLists.txt
Expand Down
Empty file added logger/include/CMakeLists.txt
Empty file.
1 change: 1 addition & 0 deletions logger/include/gz/utils/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
gz_install_all_headers(COMPONENT logger)
58 changes: 58 additions & 0 deletions logger/include/gz/utils/logger/LogMessage.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
/*
* Copyright (C) 2024 Open Source Robotics Foundation
*
* 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 GZ_UTILS_LOGGER_LOGMESSAGE_HH_
#define GZ_UTILS_LOGGER_LOGMESSAGE_HH_

#include <spdlog/spdlog.h>

#include <iosfwd>
#include <sstream>

namespace gz::utils::logger
{

class LogMessage
{
/// \brief Constructor.
/// \param[in] _logLevel Log level.
public: explicit LogMessage(spdlog::level::level_enum _logLevel,
const char *_logger = nullptr,
const char *_file = nullptr,
int _line = -1);

/// \brief Destructor.
public: ~LogMessage();

/// \brief Get access to the underlying stream.
/// \return The underlying stream.
public: std::ostream &stream();

/// \brief Log level.
private: spdlog::level::level_enum severity;

private: std::shared_ptr<spdlog::logger> logger;

/// \brief Source file location information.
private: spdlog::source_loc sourceLocation;

/// \brief Underlying stream.
private: std::ostringstream ss;
};
} // namespace gz::utils::logger

#endif // GZ_UTILS_LOGGER_LOGMESSAGE_HH_
168 changes: 168 additions & 0 deletions logger/include/gz/utils/logger/SplitSink.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,168 @@
/*
* Copyright (C) 2024 Open Source Robotics Foundation
*
* 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 GZ_UTILS_LOGGER_SPLITSINK_HH_
#define GZ_UTILS_LOGGER_SPLITSINK_HH_

#include <string>

#include <spdlog/details/log_msg.h>
#include <spdlog/details/null_mutex.h>
#include <spdlog/details/console_globals.h>
#include <spdlog/pattern_formatter.h>

#include <spdlog/sinks/base_sink.h>
#include <spdlog/sinks/ringbuffer_sink.h>
#include <spdlog/sinks/stdout_color_sinks.h>

namespace gz::utils::logger
{
/// \brief Logging sink for spdlog that logs in Gazebo-conventions
///
/// This will route messages with severity (warn, err, critical) to stderr,
/// and all other levels (info, debug, trace) to stdout
template<typename Mutex>
class SplitConsoleSink : public spdlog::sinks::base_sink<Mutex>
{
public: SplitConsoleSink() = default;
public: SplitConsoleSink(const SplitConsoleSink &) = delete;
public: SplitConsoleSink &operator=(const SplitConsoleSink &) = delete;

protected: void sink_it_(const spdlog::details::log_msg &_msg) override
{
if (!this->should_log(_msg.level))
{
return;
}

if (_msg.level == spdlog::level::warn ||
_msg.level == spdlog::level::err ||
_msg.level == spdlog::level::critical)
{
this->stderr.log(_msg);
}
else
this->stdout.log(_msg);
}

protected: void flush_() override
{
this->stdout.flush();
this->stderr.flush();
}

void set_pattern_(const std::string &pattern) override
{
this->set_formatter_(spdlog::details::make_unique<spdlog::pattern_formatter>(pattern));
}

void set_formatter_(std::unique_ptr<spdlog::formatter> sink_formatter) override
{
spdlog::sinks::base_sink<Mutex>::formatter_ = std::move(sink_formatter);
this->stdout.set_formatter(spdlog::sinks::base_sink<Mutex>::formatter_->clone());
this->stderr.set_formatter(spdlog::sinks::base_sink<Mutex>::formatter_->clone());
}

/// \brief Standard output.
private: spdlog::sinks::stdout_color_sink_st stdout;

/// \brief Standard error.
private: spdlog::sinks::stderr_color_sink_st stderr;
};

using SplitConsoleSinkMt = SplitConsoleSink<std::mutex>;
using SplitConsoleSinkSt = SplitConsoleSink<spdlog::details::null_mutex>;

/// \brief Logging sink for spdlog that logs in Gazebo-conventions
///
/// This will route messages with severity (warn, err, critical) to stderr,
/// and all other levels (info, debug, trace) to stdout
template<typename Mutex, size_t n_items>
class SplitRingBufferSink: public spdlog::sinks::base_sink<Mutex>
{
public: SplitRingBufferSink() = default;
public: SplitRingBufferSink(const SplitRingBufferSink &) = delete;
public: SplitRingBufferSink &operator=(const SplitRingBufferSink &) = delete;

public: std::vector<spdlog::details::log_msg_buffer> last_raw_stdout(size_t lim = 0)
{
return this->stdout.last_raw(lim);
}

public: std::vector<spdlog::details::log_msg_buffer> last_raw_stderr(size_t lim = 0)
{
return this->stderr.last_raw(lim);
}

public: std::vector<std::string> last_formatted_stdout(size_t lim = 0)
{
return this->stdout.last_formatted(lim);
}

public: std::vector<std::string> last_formatted_stderr(size_t lim = 0)
{
return this->stderr.last_formatted(lim);
}

protected: void sink_it_(const spdlog::details::log_msg &_msg) override
{
if (!this->should_log(_msg.level))
{
return;
}

if (_msg.level == spdlog::level::warn ||
_msg.level == spdlog::level::err ||
_msg.level == spdlog::level::critical)
{
this->stderr.log(_msg);
}
else
this->stdout.log(_msg);
}

protected: void flush_() override
{
this->stdout.flush();
this->stderr.flush();
}

protected: void set_pattern_(const std::string &pattern) override
{
this->set_formatter_(spdlog::details::make_unique<spdlog::pattern_formatter>(pattern));
}

protected: void set_formatter_(std::unique_ptr<spdlog::formatter> sink_formatter) override
{
spdlog::sinks::base_sink<Mutex>::formatter_ = std::move(sink_formatter);
this->stdout.set_formatter(spdlog::sinks::base_sink<Mutex>::formatter_->clone());
this->stderr.set_formatter(spdlog::sinks::base_sink<Mutex>::formatter_->clone());
}


/// \brief Standard output.
private: spdlog::sinks::ringbuffer_sink_st stdout {n_items};

/// \brief Standard error.
private: spdlog::sinks::ringbuffer_sink_st stderr {n_items};
};

template <size_t n_items>
using SplitRingBufferSinkMt = SplitRingBufferSink<std::mutex, n_items>;

} // namespace gz::utils::logger
#endif // GZ_UTILS_LOGGER_SPLITSINK_HH__
14 changes: 14 additions & 0 deletions logger/src/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
gz_get_libsources_and_unittests(sources gtest_sources)

gz_add_component(
logger
SOURCES ${sources}
INDEPENDENT_FROM_PROJECT_LIB
GET_TARGET_NAME gz_utils_logger_target_name)

target_link_libraries(${gz_utils_logger_target_name} PUBLIC spdlog::spdlog)

gz_build_tests(TYPE UNIT
SOURCES ${gtest_sources}
LIB_DEPS ${gz_utils_logger_target_name}
)
50 changes: 50 additions & 0 deletions logger/src/LogMessage.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
/*
* Copyright (C) 2024 Open Source Robotics Foundation
*
* 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 <spdlog/spdlog.h>
#include <gz/utils/logger/LogMessage.hh>

namespace gz::utils::logger
{
/////////////////////////////////////////////////
LogMessage::LogMessage(spdlog::level::level_enum _logLevel,
const char *_logger,
const char *_file,
int _line):
severity(_logLevel),
logger(_logger == nullptr ? spdlog::default_logger() : spdlog::get(_logger)),
sourceLocation(_file, _line, "")
{
}

/////////////////////////////////////////////////
LogMessage::~LogMessage()
{
if (sourceLocation.filename != nullptr)
{
logger->log(this->sourceLocation, this->severity, this->ss.str());
} else {
logger->log(this->severity, this->ss.str());
}
}
/////////////////////////////////////////////////
std::ostream &LogMessage::stream()
{
return this->ss;
}

} // namespace gz::utils::logger
69 changes: 69 additions & 0 deletions logger/src/SplitSink_TEST.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
/*
* Copyright (C) 2024 Open Source Robotics Foundation
*
* 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 <gtest/gtest.h>

#include <spdlog/logger.h>

#include <gz/utils/logger/SplitSink.hh>

/////////////////////////////////////////////////
TEST(SplitConsoleSink, foo)
{
auto split_sink = std::make_shared<gz::utils::logger::SplitConsoleSinkMt>();

spdlog::logger logger("split_sink", {split_sink});
logger.set_level(spdlog::level::trace);

logger.trace("trace");
logger.debug("debug");
logger.info("info");
logger.warn("warn");
logger.error("error");
logger.critical("critical");
}

/////////////////////////////////////////////////
TEST(SplitRingBufferSink, foo)
{
auto split_sink = std::make_shared<gz::utils::logger::SplitRingBufferSinkMt<100>>();
auto split_sink_console = std::make_shared<gz::utils::logger::SplitConsoleSinkMt>();

spdlog::logger logger("split_sink", {split_sink, split_sink_console});
logger.set_level(spdlog::level::trace);

logger.trace("trace");
logger.debug("debug");
logger.info("info");
logger.warn("warn");
logger.error("error");
logger.critical("critical");

{
auto logs = split_sink->last_raw_stdout();
EXPECT_EQ(logs[0].payload, "trace");
EXPECT_EQ(logs[1].payload, "debug");
EXPECT_EQ(logs[2].payload, "info");
}

{
auto logs = split_sink->last_raw_stderr();
EXPECT_EQ(logs[0].payload, "warn");
EXPECT_EQ(logs[1].payload, "error");
EXPECT_EQ(logs[2].payload, "critical");
}
}

0 comments on commit 965eff9

Please sign in to comment.