diff --git a/CMakeLists.txt b/CMakeLists.txt index dddf8c4..3c2891d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -27,8 +27,8 @@ if(CACTUS_RT_ENABLE_FETCH_DEPENDENCIES) FetchContent_Declare( quill GIT_REPOSITORY https://github.com/odygrd/quill.git - GIT_TAG 9a270d5d6f57a3ac19451292e3a9f370fcd744b1 - # GIT_TAG v3.3.2 + # GIT_TAG a058985253dffd6a77b4eeca3ba4aa5ad85a2d02 + GIT_TAG v7.3.0 ) FetchContent_MakeAvailable(quill) @@ -117,6 +117,7 @@ add_library(cactus_rt src/cactus_rt/thread.cc src/cactus_rt/cyclic_thread.cc src/cactus_rt/signal_handler.cc + src/cactus_rt/logging.cc src/cactus_rt/experimental/lockless/atomic_bitset.cc ) @@ -133,9 +134,6 @@ target_link_libraries(cactus_rt Threads::Threads ) -# Use a bounded queue -target_compile_definitions(cactus_rt PUBLIC QUILL_USE_BOUNDED_QUEUE) - if(${CMAKE_PROJECT_NAME} STREQUAL ${PROJECT_NAME}) if (ENABLE_TRACING) target_sources(cactus_rt diff --git a/examples/logging_example/README.md b/examples/logging_example/README.md index 0b60003..bad547e 100644 --- a/examples/logging_example/README.md +++ b/examples/logging_example/README.md @@ -1,6 +1,85 @@ `logging_example` ================ -A simple example showing how to configure logging. Cactus RT uses [Quill](https://github.com/odygrd/quill) as a logger. +A simple example showing how to configure logging. Cactus RT uses [Quill](https://github.com/odygrd/quill) as a logger. Read the [Quill documentation](https://quillcpp.readthedocs.io/en/latest/) for details and additional examples. -To configure logging, create your own `quill::Config` and pass it to the `App` constructor. Configuration options for Quill can be found in the [Quill documentation](https://quillcpp.readthedocs.io/en/latest/users-api.html#config-class). The log format can also be configured, as per the [formatting documetnation](https://quillcpp.readthedocs.io/en/latest/users-api.html#config-class). +## `cactus_rt/logging.h` + +To use Quill in a real-time friendly manner, `include/cactus_rt/logging.h` defines important types, default settings and utilities. + +**Important**: `cactus_rt::logging::Logger` and `cactus_rt::logging::Frontend` types which define a `quill::QueueType::BoundedDropping` queue to prevent delays in case the loggers overflow, which is essential in any real-time thread. These *must* be used throughout the application instead of the default `quill::Logger` and `quill::Frontend` types! + +## Logging non-primitive STL types + +Logging non-primitive types on the hot path (i.e. in a real-time thread) requires some additional work. Most often-used standard library types are already provided for you by Quill though, and only require a simple `#include`. + +For example, when logging `std::chrono` types, you need to insert the following: + +```cpp +#include "quill/LogMacros.h" +// Required to parse std::chrono inside logging macros +#include "quill/std/Chrono.h" // IWYU pragma: keep + +... + +LOG_INFO(logger, "Time: {}", std::chrono::seconds(3)); +``` + +The [Quill Cheat Sheet](https://quillcpp.readthedocs.io/en/latest/cheat_sheet.html#) contains very useful information for logging various non-primitive types. + +## Default logging + +If unspecified, each thread will create a default logger for itself. This logger will write to a default console sink and uses a default format. All of these defaults can be found in `include/cactus_rt/logging.h`. + +## Customize logger, sink(s) or pattern format + +Customization of the quill Backend worker thread can be done by passing in logging options to the `cactus_rt::AppConfig`. + +To use a custom sink or pattern format, define them before creating the logger. The sink(s) and pattern format are used to create the logger. Finally, the name of the created logger must be passed to the `cactus_rt::ThreadConfig`. + +The snippets below might help + +1. Create a sink (see the [Quill documentation on sink types](https://quillcpp.readthedocs.io/en/latest/sink_types.html) for the full code to create each sink). + + ```cpp + // Default console sink + auto console_sink = cactus_rt::logging::DefaultConsoleSink(); + + // Custom sink, e.g. a file sink + // !! Make sure to use `cactus_rt::logging::Frontend instead of quill::Frontend !! + auto file_sink = cactus_rt::logging::Frontend::create_or_get_sink(...); + ``` + +2. Create a pattern format + + ```cpp + // Default formatter pattern + auto pattern_format = cactus_rt::logging::DefaultPatternFormatterOptions(); + + // Custom formatter pattern + auto pattern_format = quill::PatternFormatterOptions(...); + ``` + +3. Create the logger + + ```cpp + // Create custom logger using a single sink + // !! Make sure to use `cactus_rt::logging::Frontend instead of quill::Frontend !! + auto* custom_logger = cactus_rt::logging::Frontend::create_or_get_logger("CustomLogger", console_sink, pattern_format); + + // Alternatively, you can add multiple sinks to a vector and pass that instead + const std::vector> sinks = {console_sink, file_sink}; + // !! Make sure to use `cactus_rt::logging::Frontend instead of quill::Frontend !! + auto* custom_logger = cactus_rt::logging::Frontend::create_or_get_logger("CustomLogger", sinks, pattern_format); + ``` + +4. Pass the logger to the thread + + ```cpp + // Add the custom logger name to the thread config + cactus_rt::ThreadConfig thread_config; + thread_config.logger_name = custom_logger->get_logger_name(); + + // Finally, create the thread with using the thread config + auto thread = app.CreateThread("ExampleRTThread", thread_config); + ``` diff --git a/examples/logging_example/main.cc b/examples/logging_example/main.cc index d6e7c23..62807ea 100644 --- a/examples/logging_example/main.cc +++ b/examples/logging_example/main.cc @@ -3,6 +3,13 @@ #include #include +#include "quill/backend/BackendOptions.h" +#include "quill/sinks/ConsoleSink.h" +#include "quill/sinks/FileSink.h" + +// Required to parse std::chrono inside logging macros +#include "quill/std/Chrono.h" // IWYU pragma: keep + using cactus_rt::App; using cactus_rt::CyclicThread; @@ -29,10 +36,82 @@ class ExampleRTThread : public CyclicThread { } protected: - LoopControl Loop(int64_t /*now*/) noexcept final { + LoopControl Loop(int64_t elapsed_ns) noexcept final { + loop_counter_++; + if (loop_counter_ % 1000 == 0) { + LOG_INFO(Logger(), "Loop {} ({})", loop_counter_, std::chrono::nanoseconds(elapsed_ns)); + } + + LOG_INFO_LIMIT(std::chrono::milliseconds{1500}, Logger(), "Log limit: Loop {}", loop_counter_); + return LoopControl::Continue; + } +}; + +/** + * Here we create a second real-time thread that runs at another frequency, to + * show that we can have multiple threads emitting logging data simultaneously. + */ +class SecondRTThread : public CyclicThread { + int64_t loop_counter_ = 0; + + static cactus_rt::CyclicThreadConfig MakeConfig() { + cactus_rt::CyclicThreadConfig thread_config; + thread_config.period_ns = 1'200'000; + thread_config.cpu_affinity = std::vector{2}; + thread_config.SetFifoScheduler(80); + + thread_config.logger_config.logger_name = MakeLogger(); + + return thread_config; + } + + /** + * Create a logger with multiple sinks and return the logger name. + */ + static std::string MakeLogger() { + // Use the default console logger too + // Make sure to use cactus_rt's logging Frontend instead of Quill's default + auto console_sink = cactus_rt::logging::Frontend::create_or_get_sink("OtherConsoleSink", true); + + // Create a new file sink and configuration + quill::FileSinkConfig file_sink_config; + file_sink_config.set_open_mode('w'); + file_sink_config.set_filename_append_option(quill::FilenameAppendOption::StartDateTime); + // !! Make sure to use `cactus_rt::logging::Frontend instead of quill::Frontend !! + auto file_sink = cactus_rt::logging::Frontend::create_or_get_sink( + "file_logging_example.log", + file_sink_config, + quill::FileEventNotifier{} + ); + + // Add both sinks to a vector + const std::vector> sinks = {console_sink, file_sink}; + + // Create a custom formatter pattern + auto pattern_format = quill::PatternFormatterOptions( + "[%(time)][%(log_level_short_code)][%(logger)][%(process_id)][%(file_name):%(line_number)] - WOW custom message format - %(message)", + "%H:%M:%S.%Qns" + ); + + // Use the new sinks and pattern to create a custom logger for the other thread + auto* custom_thread_logger = cactus_rt::logging::Frontend::create_or_get_logger("CustomThreadLogger", sinks, pattern_format); + + // Return the custom logger's name to pass into the configuration + return custom_thread_logger->get_logger_name(); + } + + public: + SecondRTThread() : CyclicThread("SecondRTThread", MakeConfig()) {} + + int64_t GetLoopCounter() const { + return loop_counter_; + } + + protected: + LoopControl Loop(int64_t elapsed_ns) noexcept final { loop_counter_++; if (loop_counter_ % 1000 == 0) { - LOG_INFO(Logger(), "Loop {}", loop_counter_); + LOG_INFO(Logger(), "Loop {} ({})", loop_counter_, std::chrono::nanoseconds(elapsed_ns)); } LOG_INFO_LIMIT(std::chrono::milliseconds{1500}, Logger(), "Log limit: Loop {}", loop_counter_); @@ -44,15 +123,21 @@ int main() { // Create a cactus_rt app configuration cactus_rt::AppConfig app_config; - // Disable strict timestamp order - this will be faster, but logs may appear out of order - app_config.logger_config.backend_thread_strict_log_timestamp_order = false; + // Create a Quill backend logging config to configure the Quill backend thread + app_config.logger_backend_options = cactus_rt::logging::DefaultBackendOptions(); + + // Disable strict timestamp order by setting the grace period to 0 - this will be faster, but logs may appear out of order + // See quill::BackendOptions documentation for more info + // TODO: There is a bug in quill where setting the grace period to 0 causes assertion error in Debug builds. This is fixed in 7.4.0 (https://github.com/odygrd/quill/issues/605) + app_config.logger_backend_options.log_timestamp_ordering_grace_period = std::chrono::microseconds(1); // Set the background logging thread CPU affinity - app_config.logger_config.backend_thread_cpu_affinity = 1; // Different CPU than the CyclicThread CPU! + app_config.logger_backend_options.cpu_affinity = 1; // Different CPU than the CyclicThread CPU! App app("LoggingExampleApp", app_config); auto thread = app.CreateThread(); + auto other_thread = app.CreateThread(); constexpr unsigned int time = 5; diff --git a/examples/message_passing_example/data_logger_thread.cc b/examples/message_passing_example/data_logger_thread.cc index 97290da..cc73dbe 100644 --- a/examples/message_passing_example/data_logger_thread.cc +++ b/examples/message_passing_example/data_logger_thread.cc @@ -1,6 +1,7 @@ #include "data_logger_thread.h" #include +#include DataLogger::DataLogger( const std::string& data_file_path, diff --git a/examples/message_passing_example/rt_thread.cc b/examples/message_passing_example/rt_thread.cc index 6028bd8..b5bb192 100644 --- a/examples/message_passing_example/rt_thread.cc +++ b/examples/message_passing_example/rt_thread.cc @@ -1,5 +1,7 @@ #include "rt_thread.h" +#include + cactus_rt::CyclicThread::LoopControl RtThread::Loop(int64_t ellapsed_ns) noexcept { const double ellapsed_ms = static_cast(ellapsed_ns) / 1'000'000.0; diff --git a/examples/ros2/publisher/complex_data.cc b/examples/ros2/publisher/complex_data.cc index 0a90790..55383b9 100644 --- a/examples/ros2/publisher/complex_data.cc +++ b/examples/ros2/publisher/complex_data.cc @@ -70,7 +70,7 @@ class RTROS2PublisherThread : public cactus_rt::CyclicThread, public cactus_rt:: const auto elapsed_ns_f = static_cast(elapsed_ns); - MyCoefficientData msg{ + const MyCoefficientData msg{ elapsed_ns_f, elapsed_ns_f / 10.0F, elapsed_ns_f / 100.0F, diff --git a/examples/simple_example/main.cc b/examples/simple_example/main.cc index bd89d20..850d473 100644 --- a/examples/simple_example/main.cc +++ b/examples/simple_example/main.cc @@ -3,6 +3,9 @@ #include #include +// Required to parse std::chrono inside logging macros +#include "quill/std/Chrono.h" // IWYU pragma: keep + using cactus_rt::App; using cactus_rt::CyclicThread; diff --git a/examples/tracing_example_no_rt/main.cc b/examples/tracing_example_no_rt/main.cc index 86bc64f..b14ac10 100644 --- a/examples/tracing_example_no_rt/main.cc +++ b/examples/tracing_example_no_rt/main.cc @@ -3,6 +3,8 @@ #include #include +#include "quill/Backend.h" // Required to start/stop the quill backend thread + using namespace std::chrono_literals; using FileSink = cactus_rt::tracing::FileSink; using TraceAggregator = cactus_rt::tracing::TraceAggregator; @@ -25,7 +27,7 @@ void StartTracing(const char* app_name, const char* filename) { // Create the file sink so the data aggregated by the TraceAggregator will be written to somewhere. auto file_sink = std::make_shared(filename); - quill::start(); + quill::Backend::start(); trace_aggregator->Start(file_sink); } diff --git a/include/cactus_rt/app.h b/include/cactus_rt/app.h index c2907ad..1d07c54 100644 --- a/include/cactus_rt/app.h +++ b/include/cactus_rt/app.h @@ -8,7 +8,6 @@ #include #include "config.h" -#include "quill/Quill.h" #include "thread.h" #include "tracing/thread_tracer.h" #include "tracing/trace_aggregator.h" @@ -29,7 +28,7 @@ class App { size_t heap_size_; // Configuration for quill logging - quill::Config logger_config_; + quill::BackendOptions logger_backend_options_; TracerConfig tracer_config_; @@ -37,18 +36,6 @@ class App { std::vector> threads_; - void SetDefaultLogFormat(quill::Config& cfg) { - // Create a handler of stdout - const std::shared_ptr handler = quill::stdout_handler(); - - // Enable console colours on the handler - static_cast(handler.get())->enable_console_colours(); - - // Set the default pattern - handler->set_pattern("[%(ascii_time)][%(level_id)][%(logger_name)][%(filename):%(lineno)] %(message)", "%Y-%m-%d %H:%M:%S.%Qns"); - cfg.default_handlers.push_back(handler); - } - public: explicit App(std::string name = "RTApp", AppConfig config = AppConfig()); diff --git a/include/cactus_rt/config.h b/include/cactus_rt/config.h index 73d9e9a..7dcf851 100644 --- a/include/cactus_rt/config.h +++ b/include/cactus_rt/config.h @@ -1,11 +1,11 @@ #ifndef CACTUS_RT_CONFIG_H_ #define CACTUS_RT_CONFIG_H_ -#include - #include +#include "cactus_rt/logging.h" #include "cactus_rt/scheduler.h" +#include "quill/backend/BackendOptions.h" namespace cactus_rt { @@ -29,9 +29,11 @@ struct AppConfig { size_t heap_size = 0; /** - * @brief The configuration for quill logging + * @brief The Quill Backend configuration for logging. + * + * It is set to sensible default values for real-time logging. */ - quill::Config logger_config; + quill::BackendOptions logger_backend_options = cactus_rt::logging::DefaultBackendOptions(); /** * @brief The config for the tracer if enabled (ENABLE_TRACING option in cmake) @@ -99,6 +101,20 @@ struct ThreadTracerConfig { bool trace_wakeup_latency = false; }; +/** + * @brief The configuration needed for Quill logging in a thread + */ +struct ThreadLoggerConfig { + /** + * @brief Name of the logger that is to be used as thread logger. + * + * @note If not given, a default thread logger is created with the name set to the thread name. + * + * @note If the name given does not correspond to a created logger, a default thread logger is created with the `logger_name`. + */ + std::string logger_name; +}; + /** * @brief The configuration required for a thread */ @@ -111,6 +127,8 @@ struct ThreadConfig { ThreadTracerConfig tracer_config; + ThreadLoggerConfig logger_config; + // The scheduler type, default scheduler is SCHED_OTHER std::shared_ptr scheduler = std::make_shared(); diff --git a/include/cactus_rt/logging.h b/include/cactus_rt/logging.h new file mode 100644 index 0000000..afb3c42 --- /dev/null +++ b/include/cactus_rt/logging.h @@ -0,0 +1,104 @@ +#ifndef CACTUS_RT_LOGGING_H_ +#define CACTUS_RT_LOGGING_H_ + +#include +#include +#include + +#include "quill/Frontend.h" +#include "quill/Logger.h" +#include "quill/backend/BackendOptions.h" +#include "quill/core/Common.h" +#include "quill/core/PatternFormatterOptions.h" +#include "quill/sinks/Sink.h" + +// The quill logging macros are explicitly included in this header file. +// This is convenience to prevent another #include when using cactus_rt logging. +#include "quill/LogMacros.h" // IWYU pragma: export + +namespace cactus_rt::logging { +/** + * Defines a Bounded Dropping queue, to drop logging messages if the buffers + * fill up. This prevents run-time reallocations. + + * FrontendOptions are compile-time options and must be passed as a + * template argument. + * + * Based on: + * - https://github.com/odygrd/quill/blob/v7.3.0/examples/custom_frontend_options.cpp + * - https://quillcpp.readthedocs.io/en/latest/frontend_options.html + */ +struct BoundedDroppingFrontendOptions { + static constexpr quill::QueueType queue_type = quill::QueueType::BoundedDropping; + static constexpr uint32_t initial_queue_capacity = 128 * 1024; // 128 KiB + static constexpr uint32_t blocking_queue_retry_interval_ns = 800; // Ignored for Dropping queue + static constexpr bool huge_pages_enabled = false; +}; + +/// Type alias for `BoundedDroppingFrontendOptions` +using FrontendOptions = BoundedDroppingFrontendOptions; + +/** + * Define a quill::Frontend class using the custom options. This Frontend must + * be used consistently throughout the application instead of the default + * `quill::Frontend`. + * + * FrontendOptions are compile-time options and must be passed as a template + * argument. + */ +using BoundedDroppingFrontend = quill::FrontendImpl; + +/// Type alias for `BoundedDroppingFrontend` +using Frontend = BoundedDroppingFrontend; + +/** + * Define a custom quill::Logger to also use the custom options. This Logger + * must be used consistently throughout the application instead of the default + * `quill::Logger`. + * + * FrontendOptions are compile-time options and must be passed as a template + * argument. + */ +using BoundedDroppingLogger = quill::LoggerImpl; + +/// Type alias for `BoundedDroppingLogger` +using Logger = BoundedDroppingLogger; + +/** + * Sets `quill:BackendOptions` to suitable defaults for real-time logging. + * + * @return quill::BackendOptions + */ +quill::BackendOptions DefaultBackendOptions(); + +std::string DefaultConsoleSinkName(); + +/** + * Create a default ConsoleSink object with console colours. The name of this + * sink is defined by `cactus_rt::logging::DefaultConsoleSinkName()`. + * + * @note If this is not the first call to this function, a pointer to the + * existing default console sink is returned instead of creating a new one. + * + * @return A pointer to the sink. + */ +std::shared_ptr DefaultConsoleSink(); + +/** + * Get a default pattern format. + */ +quill::PatternFormatterOptions DefaultPatternFormatterOptions(); + +/** + * Create or get a Logger object with default settings which will write logs to + * the console with a default format. + * + * @param logger_name The logger name to use. + * @return A pointer to the created logger. If a logger with that name already + * existed, a pointer to the existing logger is returned instead. + */ +cactus_rt::logging::Logger* DefaultLogger(std::string logger_name); + +} // namespace cactus_rt::logging + +#endif diff --git a/include/cactus_rt/ros2/publisher.h b/include/cactus_rt/ros2/publisher.h index c8fd498..60ba2ff 100644 --- a/include/cactus_rt/ros2/publisher.h +++ b/include/cactus_rt/ros2/publisher.h @@ -7,7 +7,8 @@ #include #include -#include "quill/Quill.h" +#include "cactus_rt/logging.h" +#include "quill/LogMacros.h" namespace cactus_rt::ros2 { class Ros2Adapter; @@ -31,7 +32,7 @@ class Publisher : public IPublisher { using NoConversion = std::is_same; using AdaptedRosType = typename std::conditional_t>; - quill::Logger* logger_; + cactus_rt::logging::Logger* logger_; typename rclcpp::Publisher::SharedPtr publisher_; moodycamel::ReaderWriterQueue queue_; @@ -77,11 +78,11 @@ class Publisher : public IPublisher { } static std::shared_ptr> Create( - quill::Logger* logger, - rclcpp::Node& node, - const std::string& topic_name, - const rclcpp::QoS& qos, - const size_t rt_queue_size = 1000 + cactus_rt::logging::Logger* logger, + rclcpp::Node& node, + const std::string& topic_name, + const rclcpp::QoS& qos, + const size_t rt_queue_size = 1000 ) { return std::shared_ptr>( new Publisher( @@ -93,7 +94,7 @@ class Publisher : public IPublisher { } Publisher( - quill::Logger* logger, + cactus_rt::logging::Logger* logger, typename rclcpp::Publisher::SharedPtr publisher, moodycamel::ReaderWriterQueue&& queue ) : logger_(logger), publisher_(publisher), queue_(std::move(queue)) {} diff --git a/include/cactus_rt/ros2/ros2_adapter.h b/include/cactus_rt/ros2/ros2_adapter.h index da9c572..ce05a89 100644 --- a/include/cactus_rt/ros2/ros2_adapter.h +++ b/include/cactus_rt/ros2/ros2_adapter.h @@ -10,8 +10,8 @@ #include #include +#include "cactus_rt/logging.h" #include "publisher.h" -#include "quill/Quill.h" #include "subscription.h" namespace cactus_rt::ros2 { @@ -44,7 +44,7 @@ class Ros2Adapter { std::vector> publishers_; std::vector> subscriptions_; - quill::Logger* logger_; + cactus_rt::logging::Logger* logger_; public: Ros2Adapter(const std::string& name_, const Config& config); diff --git a/include/cactus_rt/ros2/subscription.h b/include/cactus_rt/ros2/subscription.h index 67bd856..99474d3 100644 --- a/include/cactus_rt/ros2/subscription.h +++ b/include/cactus_rt/ros2/subscription.h @@ -9,7 +9,7 @@ #include #include "../experimental/lockless/spsc/realtime_readable_value.h" -#include "quill/Quill.h" +#include "cactus_rt/logging.h" // Note: ROS subscription dispatch is here: https://github.com/ros2/rclcpp/blob/e10728c/rclcpp/include/rclcpp/any_subscription_callback.hpp#L481 // We are using the TypeAdapter method. @@ -43,7 +43,7 @@ class SubscriptionLatest : public ISubscription { using RealtimeReadableValue = cactus_rt::experimental::lockless::spsc::RealtimeReadableValue>; - quill::Logger* logger_; + cactus_rt::logging::Logger* logger_; typename rclcpp::Subscription::SharedPtr ros_subscription_; int64_t current_msg_id_ = 0; RealtimeReadableValue latest_value_; @@ -60,10 +60,10 @@ class SubscriptionLatest : public ISubscription { } static std::shared_ptr> Create( - quill::Logger* logger, - rclcpp::Node& node, - const std::string& topic_name, - const rclcpp::QoS& qos + cactus_rt::logging::Logger* logger, + rclcpp::Node& node, + const std::string& topic_name, + const rclcpp::QoS& qos ) { std::shared_ptr> subscription( new SubscriptionLatest(logger) @@ -81,7 +81,7 @@ class SubscriptionLatest : public ISubscription { return subscription; } - explicit SubscriptionLatest(quill::Logger* logger) : logger_(logger) {} + explicit SubscriptionLatest(cactus_rt::logging::Logger* logger) : logger_(logger) {} public: StampedValue ReadLatest() noexcept { @@ -100,7 +100,7 @@ class SubscriptionQueued : public ISubscription { using Queue = moodycamel::ReaderWriterQueue>; - quill::Logger* logger_; + cactus_rt::logging::Logger* logger_; typename rclcpp::Subscription::SharedPtr ros_subscription_; int64_t current_msg_id_ = 0; Queue queue_; @@ -114,11 +114,11 @@ class SubscriptionQueued : public ISubscription { } static std::shared_ptr> Create( - quill::Logger* logger, - rclcpp::Node& node, - const std::string& topic_name, - const rclcpp::QoS& qos, - const size_t rt_queue_size = 1000 + cactus_rt::logging::Logger* logger, + rclcpp::Node& node, + const std::string& topic_name, + const rclcpp::QoS& qos, + const size_t rt_queue_size = 1000 ) { std::shared_ptr> subscription( new SubscriptionQueued( @@ -140,7 +140,7 @@ class SubscriptionQueued : public ISubscription { } SubscriptionQueued( - quill::Logger* logger, + cactus_rt::logging::Logger* logger, moodycamel::ReaderWriterQueue>&& queue ) : logger_(logger), queue_(std::move(queue)) {} diff --git a/include/cactus_rt/rt.h b/include/cactus_rt/rt.h index b4765ae..285a814 100644 --- a/include/cactus_rt/rt.h +++ b/include/cactus_rt/rt.h @@ -1,5 +1,6 @@ #include "app.h" #include "cyclic_thread.h" +#include "logging.h" #include "mutex.h" #include "signal_handler.h" #include "thread.h" diff --git a/include/cactus_rt/thread.h b/include/cactus_rt/thread.h index 336a3f3..41cf2ba 100644 --- a/include/cactus_rt/thread.h +++ b/include/cactus_rt/thread.h @@ -9,7 +9,7 @@ #include #include "config.h" -#include "quill/Quill.h" +#include "logging.h" #include "tracing/thread_tracer.h" #include "tracing/trace_aggregator.h" @@ -30,7 +30,7 @@ class Thread { std::vector cpu_affinity_; size_t stack_size_; - quill::Logger* logger_; + cactus_rt::logging::Logger* logger_; // Use the custom BoundedDroppingLogger std::shared_ptr tracer_ = nullptr; std::atomic_bool stop_requested_ = false; @@ -59,11 +59,18 @@ class Thread { : config_(config), name_(name), cpu_affinity_(config_.cpu_affinity), - stack_size_(static_cast(PTHREAD_STACK_MIN) + config_.stack_size), - logger_(quill::create_logger(name_)) { + stack_size_(static_cast(PTHREAD_STACK_MIN) + config_.stack_size) { if (!config.scheduler) { throw std::runtime_error("ThreadConfig::scheduler cannot be nullptr"); } + + if (!config.logger_config.logger_name.empty()) { + // If a logger name was passed in the thread configuration, get or create it + logger_ = cactus_rt::logging::DefaultLogger(config_.logger_config.logger_name); + } else { + // If no logger name was passed in the thread configuration, create a new one using the thread name + logger_ = cactus_rt::logging::DefaultLogger(this->Name()); + } } public: @@ -94,7 +101,7 @@ class Thread { // The constructors and destructors are needed because we need to delete // objects of type Thread polymorphically, through the map in the App class. - virtual ~Thread() = default; + virtual ~Thread(); // Copy constructors are not allowed Thread(const Thread&) = delete; @@ -118,7 +125,7 @@ class Thread { void Start(int64_t start_monotonic_time_ns); protected: - inline quill::Logger* Logger() const { return logger_; } + inline cactus_rt::logging::Logger* Logger() const { return logger_; } /** * Gets the current tracer object. Should only ever be called from within the thread itself. diff --git a/include/cactus_rt/tracing/trace_aggregator.h b/include/cactus_rt/tracing/trace_aggregator.h index 3b9965b..1cda95c 100644 --- a/include/cactus_rt/tracing/trace_aggregator.h +++ b/include/cactus_rt/tracing/trace_aggregator.h @@ -4,8 +4,6 @@ #ifndef CACTUS_RT_TRACING_ENABLED #include "trace_aggregator.disabled.h" #else -#include - #include #include #include @@ -14,6 +12,7 @@ #include #include +#include "cactus_rt/logging.h" #include "sink.h" #include "thread_tracer.h" @@ -43,7 +42,8 @@ class TraceAggregator { const std::string process_name_; const uint64_t process_track_uuid_; - quill::Logger* logger_; + + cactus_rt::logging::Logger* logger_; // Use the custom BoundedDroppingLogger // This mutex protects tracers_ and session_ std::mutex mutex_; @@ -61,6 +61,9 @@ class TraceAggregator { public: explicit TraceAggregator(std::string name); + // Destructor is needed to flush the logger when this thread is destroyed + ~TraceAggregator(); + // No copy no move TraceAggregator(const TraceAggregator&) = delete; TraceAggregator& operator=(const TraceAggregator&) = delete; @@ -94,7 +97,7 @@ class TraceAggregator { void Stop() noexcept; private: - quill::Logger* Logger() noexcept; + cactus_rt::logging::Logger* Logger() noexcept; void Run(); bool StopRequested() const noexcept; diff --git a/src/cactus_rt/app.cc b/src/cactus_rt/app.cc index ede9ee7..b3956f9 100644 --- a/src/cactus_rt/app.cc +++ b/src/cactus_rt/app.cc @@ -10,7 +10,7 @@ #include "cactus_rt/tracing/trace_aggregator.h" #include "cactus_rt/tracing/tracing_enabled.h" #include "cactus_rt/utils.h" -#include "quill/Quill.h" +#include "quill/Backend.h" using FileSink = cactus_rt::tracing::FileSink; @@ -19,20 +19,13 @@ namespace cactus_rt { App::App(std::string name, AppConfig config) : name_(name), heap_size_(config.heap_size), - logger_config_(config.logger_config), + logger_backend_options_(config.logger_backend_options), tracer_config_(config.tracer_config), trace_aggregator_(std::make_shared(name)) { - if (logger_config_.default_handlers.empty()) { - SetDefaultLogFormat(logger_config_); - } - - // TODO: backend_thread_notification_handler can throw - we need to handle this somehow - // logger_config_.backend_thread_notification_handler } App::~App() { StopTraceSession(); - quill::flush(); } void App::Start(int64_t start_monotonic_time_ns) { @@ -156,8 +149,7 @@ void App::ReserveHeap() const { } void App::StartQuill() { - quill::configure(logger_config_); - quill::start(); + quill::Backend::start(logger_backend_options_); } void App::StopTraceAggregator() noexcept { diff --git a/src/cactus_rt/cyclic_thread.cc b/src/cactus_rt/cyclic_thread.cc index 2421394..03e085c 100644 --- a/src/cactus_rt/cyclic_thread.cc +++ b/src/cactus_rt/cyclic_thread.cc @@ -1,6 +1,7 @@ #include "cactus_rt/cyclic_thread.h" #include "cactus_rt/utils.h" +#include "quill/LogMacros.h" namespace cactus_rt { diff --git a/src/cactus_rt/logging.cc b/src/cactus_rt/logging.cc new file mode 100644 index 0000000..c183e2b --- /dev/null +++ b/src/cactus_rt/logging.cc @@ -0,0 +1,47 @@ +#include "cactus_rt/logging.h" + +#include +#include +#include + +#include "quill/Logger.h" +#include "quill/backend/BackendOptions.h" +#include "quill/core/PatternFormatterOptions.h" +#include "quill/sinks/ConsoleSink.h" +#include "quill/sinks/Sink.h" + +quill::BackendOptions cactus_rt::logging::DefaultBackendOptions() { + // Many of the default options set by Quill are already OK for real-time logging + quill::BackendOptions default_backend_options; + + // Disable strict timestamp order by setting the grace period to 0 - this will be faster, but logs may appear out of order + // See quill::BackendOptions documentation for more info + // TODO: There is a bug in quill where setting the grace period to 0 causes assertion error in Debug builds. This is fixed in 7.4.0 (https://github.com/odygrd/quill/issues/605) + default_backend_options.log_timestamp_ordering_grace_period = std::chrono::milliseconds(1); + + return default_backend_options; +} + +cactus_rt::logging::Logger* cactus_rt::logging::DefaultLogger(std::string logger_name) { + return cactus_rt::logging::Frontend::create_or_get_logger( + logger_name, + DefaultConsoleSink(), + DefaultPatternFormatterOptions() + ); +} + +std::string cactus_rt::logging::DefaultConsoleSinkName() { return "DefaultConsoleSink"; } + +std::shared_ptr cactus_rt::logging::DefaultConsoleSink() { + return cactus_rt::logging::Frontend::create_or_get_sink( + cactus_rt::logging::DefaultConsoleSinkName(), + true // Enable console colours + ); +} + +quill::PatternFormatterOptions cactus_rt::logging::DefaultPatternFormatterOptions() { + return quill::PatternFormatterOptions( + "[%(time)][%(log_level_short_code)][%(logger)][%(file_name):%(line_number)] %(message)", + "%Y-%m-%d %H:%M:%S.%Qns" + ); +} diff --git a/src/cactus_rt/ros2/ros2_adapter.cc b/src/cactus_rt/ros2/ros2_adapter.cc index a9efc6e..c87bf17 100644 --- a/src/cactus_rt/ros2/ros2_adapter.cc +++ b/src/cactus_rt/ros2/ros2_adapter.cc @@ -2,11 +2,13 @@ #include +#include "cactus_rt/logging.h" + namespace cactus_rt::ros2 { Ros2Adapter::Ros2Adapter(const std::string& name, const Ros2Adapter::Config& config) : ros_node_(std::make_shared(name + "_ros_adapter")), - logger_(quill::create_logger("Ros2Adapter")) { + logger_(cactus_rt::logging::DefaultLogger("Ros2Adapter")) { timer_ = this->ros_node_->create_wall_timer(config.timer_interval, [this] { TimerCallback(); }); } diff --git a/src/cactus_rt/thread.cc b/src/cactus_rt/thread.cc index 89f21c7..28ce3ef 100644 --- a/src/cactus_rt/thread.cc +++ b/src/cactus_rt/thread.cc @@ -9,10 +9,23 @@ #include #include "cactus_rt/config.h" +#include "cactus_rt/logging.h" #include "cactus_rt/tracing/thread_tracer.h" +#include "quill/Backend.h" +#include "quill/LogMacros.h" namespace cactus_rt { +Thread::~Thread() { + // Flushing the logger only if the background thread is still running, + // otherwise `flush_log()` will block indefinitely. + if (quill::Backend::is_running()) { + // Blocks until all messages up to the current timestamp are flushed on the + // logger, to ensure every message is logged. + this->Logger()->flush_log(); + } +} + void* Thread::RunThread(void* data) { auto* thread = static_cast(data); @@ -37,7 +50,7 @@ void* Thread::RunThread(void* data) { ); } - quill::preallocate(); // Pre-allocates thread-local data to avoid the need to allocate on the first log message + cactus_rt::logging::Frontend::preallocate(); // Pre-allocates thread-local data to avoid the need to allocate on the first log message thread->BeforeRun(); thread->Run(); diff --git a/src/cactus_rt/tracing/trace_aggregator.cc b/src/cactus_rt/tracing/trace_aggregator.cc index b27b80d..125d3ac 100644 --- a/src/cactus_rt/tracing/trace_aggregator.cc +++ b/src/cactus_rt/tracing/trace_aggregator.cc @@ -17,6 +17,10 @@ #include #include +#include "cactus_rt/logging.h" +#include "quill/Backend.h" +#include "quill/LogMacros.h" + using cactus_tracing::vendor::perfetto::protos::InternedData; using cactus_tracing::vendor::perfetto::protos::ProcessDescriptor; using cactus_tracing::vendor::perfetto::protos::ThreadDescriptor; @@ -57,7 +61,17 @@ namespace cactus_rt::tracing { TraceAggregator::TraceAggregator(std::string process_name) : process_name_(process_name), process_track_uuid_(static_cast(getpid())), - logger_(quill::create_logger("__trace_aggregator__")) { + logger_(cactus_rt::logging::DefaultLogger("__trace_aggregator__")) { +} + +TraceAggregator::~TraceAggregator() { + // Flushing the logger only if the background thread is still running, + // otherwise `flush_log()` will block indefinitely. + if (quill::Backend::is_running()) { + // Blocks until all messages up to the current timestamp are flushed on the + // logger, to ensure every message is logged. + this->Logger()->flush_log(); + } } void TraceAggregator::RegisterThreadTracer(std::shared_ptr tracer) { @@ -129,13 +143,16 @@ void TraceAggregator::Stop() noexcept { mutex_.unlock(); } -quill::Logger* TraceAggregator::Logger() noexcept { +cactus_rt::logging::Logger* TraceAggregator::Logger() noexcept { return logger_; } void TraceAggregator::Run() { ::SetupCPUAffinityIfNecessary(session_->cpu_affinity); + // Pre-allocates thread-local data to avoid the need to allocate on the first log message + cactus_rt::logging::Frontend::preallocate(); + while (!session_->stop_requested.load(std::memory_order_relaxed)) { Trace trace; auto num_events = TryDequeueOnceFromAllTracers(trace); diff --git a/tests/tracing/multi_threaded_test.cc b/tests/tracing/multi_threaded_test.cc index 8e39374..b95ac5e 100644 --- a/tests/tracing/multi_threaded_test.cc +++ b/tests/tracing/multi_threaded_test.cc @@ -1,6 +1,6 @@ #include #include -#include +#include #include @@ -42,7 +42,7 @@ class MultiThreadTracingTest : public ::testing::Test { app_.Join(); // Need to stop it for every test as every app.Start() will start a background thread. - quill::detail::LogManagerSingleton::instance().log_manager().stop_backend_worker(); + quill::Backend::stop(); } }; diff --git a/tests/tracing/single_threaded_test.cc b/tests/tracing/single_threaded_test.cc index 5f15ade..c65f6e4 100644 --- a/tests/tracing/single_threaded_test.cc +++ b/tests/tracing/single_threaded_test.cc @@ -1,6 +1,6 @@ #include #include -#include +#include #include #include @@ -48,7 +48,7 @@ class SingleThreadTracingTest : public ::testing::Test { app_.Join(); // Need to stop it for every test as every app.Start() will start a background thread. - quill::detail::LogManagerSingleton::instance().log_manager().stop_backend_worker(); + quill::Backend::stop(); } };