Skip to content

Commit

Permalink
change flushing behavior for spdlog log files, and add env var to use…
Browse files Browse the repository at this point in the history
… old style (no explicit flushing) (#95)

* change flushing behavior for spdlog log files, and add env var to use old style (no explicit flushing)

Signed-off-by: William Woodall <william@osrfoundation.org>

* register logger with spdlog so periodic flush can work

Signed-off-by: William Woodall <william@osrfoundation.org>

* update to use make_shared instead of make_unique

Signed-off-by: William Woodall <william@osrfoundation.org>

Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood authored Nov 17, 2022
1 parent 378734e commit 0997e5d
Show file tree
Hide file tree
Showing 3 changed files with 150 additions and 4 deletions.
2 changes: 1 addition & 1 deletion rcl_logging_spdlog/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ if(BUILD_TESTING)
find_package(performance_test_fixture REQUIRED)

find_package(ament_cmake_gtest REQUIRED)
ament_add_gtest(test_logging_interface test/test_logging_interface.cpp)
ament_add_gmock(test_logging_interface test/test_logging_interface.cpp)
if(TARGET test_logging_interface)
target_link_libraries(test_logging_interface ${PROJECT_NAME})
target_compile_definitions(test_logging_interface PUBLIC RCUTILS_ENABLE_FAULT_INJECTION)
Expand Down
64 changes: 62 additions & 2 deletions rcl_logging_spdlog/src/rcl_logging_spdlog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,13 +13,15 @@
// limitations under the License.

#include <cerrno>
#include <chrono>
#include <cinttypes>
#include <memory>
#include <mutex>
#include <string>
#include <utility>

#include "rcpputils/filesystem_helper.hpp"
#include "rcpputils/env.hpp"
#include "rcutils/allocator.h"
#include "rcutils/logging.h"
#include "rcutils/process.h"
Expand All @@ -32,7 +34,7 @@
#include "rcl_logging_interface/rcl_logging_interface.h"

static std::mutex g_logger_mutex;
static std::unique_ptr<spdlog::logger> g_root_logger = nullptr;
static std::shared_ptr<spdlog::logger> g_root_logger = nullptr;

static spdlog::level::level_enum map_external_log_level_to_library_level(int external_level)
{
Expand All @@ -53,6 +55,42 @@ static spdlog::level::level_enum map_external_log_level_to_library_level(int ext
return level;
}

namespace
{

RCL_LOGGING_INTERFACE_LOCAL
bool
get_should_use_old_flushing_behavior()
{
const char * env_var_name = "RCL_LOGGING_SPDLOG_EXPERIMENTAL_OLD_FLUSHING_BEHAVIOR";

try {
std::string env_var_value = rcpputils::get_env_var(env_var_name);

if (env_var_value.empty()) {
// not set
return false;
}
if ("0" == env_var_value) {
// explicitly false
return false;
}
if ("1" == env_var_value) {
// explicitly true
return true;
}

// unknown value
throw std::runtime_error("unrecognized value: " + env_var_value);
} catch (const std::runtime_error & error) {
throw std::runtime_error(
std::string("failed to get env var '") + env_var_name + "': " + error.what()
);
}
}

} // namespace

rcl_logging_ret_t rcl_logging_external_initialize(
const char * config_file,
rcutils_allocator_t allocator)
Expand All @@ -72,6 +110,16 @@ rcl_logging_ret_t rcl_logging_external_initialize(
"spdlog logging backend doesn't currently support external configuration");
return RCL_LOGGING_RET_ERROR;
} else {
// check RCL_LOGGING_SPDLOG_EXPERIMENTAL_OLD_FLUSHING_BEHAVIOR to see if we
// should change log file flushing behavior
bool should_use_old_flushing_behavior = false;
try {
should_use_old_flushing_behavior = ::get_should_use_old_flushing_behavior();
} catch (const std::runtime_error & error) {
RCUTILS_SET_ERROR_MSG(error.what());
return RCL_LOGGING_RET_ERROR;
}

// To be compatible with ROS 1, we construct a default filename of
// the form ~/.ros/log/<exe>_<pid>_<milliseconds-since-epoch>.log

Expand Down Expand Up @@ -127,7 +175,18 @@ rcl_logging_ret_t rcl_logging_external_initialize(
}

auto sink = std::make_unique<spdlog::sinks::basic_file_sink_mt>(name_buffer, false);
g_root_logger = std::make_unique<spdlog::logger>("root", std::move(sink));
g_root_logger = std::make_shared<spdlog::logger>("root", std::move(sink));
if (!should_use_old_flushing_behavior) {
// in this case we should do the new thing (until config files are supported)
// which is to configure the logger to flush periodically and on
// error level messages
spdlog::flush_every(std::chrono::seconds(5));
g_root_logger->flush_on(spdlog::level::err);
} else {
// the old behavior is to not configure the sink at all, so do nothing
}

spdlog::register_logger(g_root_logger);

g_root_logger->set_pattern("%v");
}
Expand All @@ -137,6 +196,7 @@ rcl_logging_ret_t rcl_logging_external_initialize(

rcl_logging_ret_t rcl_logging_external_shutdown()
{
spdlog::drop("root");
g_root_logger = nullptr;
return RCL_LOGGING_RET_OK;
}
Expand Down
88 changes: 87 additions & 1 deletion rcl_logging_spdlog/test/test_logging_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#include <fstream>
#include <string>

#include "gtest/gtest.h"
#include "gmock/gmock.h"

#include "rcpputils/filesystem_helper.hpp"
#include "rcpputils/env.hpp"
Expand Down Expand Up @@ -106,6 +106,92 @@ TEST_F(LoggingTest, init_failure)
ASSERT_TRUE(rcpputils::fs::remove(fake_home));
}

TEST_F(LoggingTest, init_old_flushing_behavior)
{
RestoreEnvVar env_var("RCL_LOGGING_SPDLOG_EXPERIMENTAL_OLD_FLUSHING_BEHAVIOR");
rcpputils::set_env_var("RCL_LOGGING_SPDLOG_EXPERIMENTAL_OLD_FLUSHING_BEHAVIOR", "1");

ASSERT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_initialize(nullptr, allocator));

std::stringstream expected_log;
for (int level : logger_levels) {
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_set_logger_level(nullptr, level));

for (int severity : logger_levels) {
std::stringstream ss;
ss << "Message of severity " << severity << " at level " << level;
rcl_logging_external_log(severity, nullptr, ss.str().c_str());

if (severity >= level) {
expected_log << ss.str() << std::endl;
} else if (severity == 0 && level == 10) {
// This is a special case - not sure what the right behavior is
expected_log << ss.str() << std::endl;
}
}
}

EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_shutdown());

std::string log_file_path = find_single_log().string();
std::ifstream log_file(log_file_path);
std::stringstream actual_log;
actual_log << log_file.rdbuf();
EXPECT_EQ(
expected_log.str(),
actual_log.str()) << "Unexpected log contents in " << log_file_path;
}

TEST_F(LoggingTest, init_explicit_new_flush_behavior)
{
RestoreEnvVar env_var("RCL_LOGGING_SPDLOG_EXPERIMENTAL_OLD_FLUSHING_BEHAVIOR");
rcpputils::set_env_var("RCL_LOGGING_SPDLOG_EXPERIMENTAL_OLD_FLUSHING_BEHAVIOR", "0");

ASSERT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_initialize(nullptr, allocator));

std::stringstream expected_log;
for (int level : logger_levels) {
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_set_logger_level(nullptr, level));

for (int severity : logger_levels) {
std::stringstream ss;
ss << "Message of severity " << severity << " at level " << level;
rcl_logging_external_log(severity, nullptr, ss.str().c_str());

if (severity >= level) {
expected_log << ss.str() << std::endl;
} else if (severity == 0 && level == 10) {
// This is a special case - not sure what the right behavior is
expected_log << ss.str() << std::endl;
}
}
}

EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_shutdown());

std::string log_file_path = find_single_log().string();
std::ifstream log_file(log_file_path);
std::stringstream actual_log;
actual_log << log_file.rdbuf();
EXPECT_EQ(
expected_log.str(),
actual_log.str()) << "Unexpected log contents in " << log_file_path;
}

TEST_F(LoggingTest, init_invalid_flush_setting)
{
RestoreEnvVar env_var("RCL_LOGGING_SPDLOG_EXPERIMENTAL_OLD_FLUSHING_BEHAVIOR");
rcpputils::set_env_var("RCL_LOGGING_SPDLOG_EXPERIMENTAL_OLD_FLUSHING_BEHAVIOR", "invalid");

ASSERT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, allocator));
std::string error_state_str = rcutils_get_error_string().str;
using ::testing::HasSubstr;
ASSERT_THAT(
error_state_str,
HasSubstr("unrecognized value:"));
rcutils_reset_error();
}

TEST_F(LoggingTest, full_cycle)
{
ASSERT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_initialize(nullptr, allocator));
Expand Down

0 comments on commit 0997e5d

Please sign in to comment.