Skip to content

Commit

Permalink
Constructor
Browse files Browse the repository at this point in the history
Signed-off-by: Carlos Agüero <[email protected]>
  • Loading branch information
caguero committed Aug 19, 2024
1 parent 0ac9ddd commit 49cd5af
Show file tree
Hide file tree
Showing 3 changed files with 24 additions and 18 deletions.
2 changes: 1 addition & 1 deletion log/include/gz/utils/log/Logger.hh
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ namespace utils
{
namespace log
{
inline namespace GZ_UTILS_VERSION_NAMESPACE {
inline namespace GZ_UTILS_LOG_VERSION_NAMESPACE {

/// \brief Gazebo console and file logging class.
/// This will configure spdlog with a sane set of defaults for logging to the
Expand Down
38 changes: 22 additions & 16 deletions log/include/gz/utils/log/SplitSink.hh
Original file line number Diff line number Diff line change
Expand Up @@ -116,11 +116,18 @@ using SplitConsoleSinkSt = SplitConsoleSink<spdlog::details::null_mutex>;
///
/// 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 numItems>
template<typename Mutex>
class SplitRingBufferSink: public spdlog::sinks::base_sink<Mutex>
{
/// \brief Class constructor.
public: SplitRingBufferSink() = default;
/// \param[in] _numItems
public: explicit SplitRingBufferSink(size_t _numItems)
{
this->stdout =
std::make_shared<spdlog::sinks::ringbuffer_sink_st>(_numItems);
this->stderr =
std::make_shared<spdlog::sinks::ringbuffer_sink_st>(_numItems);
}

/// \brief No copy constructor.
public: SplitRingBufferSink(const SplitRingBufferSink &) = delete;
Expand All @@ -134,7 +141,7 @@ class SplitRingBufferSink: public spdlog::sinks::base_sink<Mutex>
public: std::vector<spdlog::details::log_msg_buffer> last_raw_stdout(
size_t _lim = 0)
{
return this->stdout.last_raw(_lim);
return this->stdout->last_raw(_lim);
}

/// \brief ToDo.
Expand All @@ -143,23 +150,23 @@ class SplitRingBufferSink: public spdlog::sinks::base_sink<Mutex>
public: std::vector<spdlog::details::log_msg_buffer> last_raw_stderr(
size_t _lim = 0)
{
return this->stderr.last_raw(_lim);
return this->stderr->last_raw(_lim);
}

/// \brief ToDo.
/// \param[in] _lim
/// \return
public: std::vector<std::string> last_formatted_stdout(size_t _lim = 0)
{
return this->stdout.last_formatted(_lim);
return this->stdout->last_formatted(_lim);
}

/// \brief ToDo.
/// \param[in] _lim
/// \return
public: std::vector<std::string> last_formatted_stderr(size_t _lim = 0)
{
return this->stderr.last_formatted(_lim);
return this->stderr->last_formatted(_lim);
}

/// \brief ToDo.
Expand All @@ -173,17 +180,17 @@ class SplitRingBufferSink: public spdlog::sinks::base_sink<Mutex>
_msg.level == spdlog::level::err ||
_msg.level == spdlog::level::critical)
{
this->stderr.log(_msg);
this->stderr->log(_msg);
}
else
this->stdout.log(_msg);
this->stdout->log(_msg);
}

/// \brief Flush messages.
protected: void flush_() override
{
this->stdout.flush();
this->stderr.flush();
this->stdout->flush();
this->stderr->flush();
}

/// \brief Set the logging pattern.
Expand All @@ -200,21 +207,20 @@ class SplitRingBufferSink: public spdlog::sinks::base_sink<Mutex>
std::unique_ptr<spdlog::formatter> _sinkFormatter) override
{
spdlog::sinks::base_sink<Mutex>::formatter_ = std::move(_sinkFormatter);
this->stdout.set_formatter(
this->stdout->set_formatter(
spdlog::sinks::base_sink<Mutex>::formatter_->clone());
this->stderr.set_formatter(
this->stderr->set_formatter(
spdlog::sinks::base_sink<Mutex>::formatter_->clone());
}

/// \brief Standard output.
private: spdlog::sinks::ringbuffer_sink_st stdout {numItems};
private: std::shared_ptr<spdlog::sinks::ringbuffer_sink_st> stdout;

/// \brief Standard error.
private: spdlog::sinks::ringbuffer_sink_st stderr {numItems};
private: std::shared_ptr<spdlog::sinks::ringbuffer_sink_st> stderr;
};

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

} // namespace GZ_UTILS_LOG_VERSION_NAMESPACE
} // namespace log
Expand Down
2 changes: 1 addition & 1 deletion log/src/SplitSink_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ TEST(SplitConsoleSink, foo)
TEST(SplitRingBufferSink, foo)
{
auto splitSink =
std::make_shared<gz::utils::log::SplitRingBufferSinkMt<100>>();
std::make_shared<gz::utils::log::SplitRingBufferSinkMt>(100);
auto splitSinkConsole =
std::make_shared<gz::utils::log::SplitConsoleSinkMt>();

Expand Down

0 comments on commit 49cd5af

Please sign in to comment.