Skip to content

Commit

Permalink
add file_name_prefix parameter to external log configuration. (#109)
Browse files Browse the repository at this point in the history
* add file_name_prefix parameter to external log configuration.

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya authored Jan 2, 2024
1 parent 4481fa6 commit fd629cf
Show file tree
Hide file tree
Showing 6 changed files with 79 additions and 28 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,10 @@ typedef enum

/// Initialize the external logging library.
/**
* \param[in] file_name_prefix The prefix for log file name that external
* logging library should use to configure itself.
* If provided, it must be a null terminated C string.
* If set to NULL or the empty string, the logging library will use defaults.
* \param[in] config_file The location of a config file that the external
* logging library should use to configure itself.
* If provided, it must be a null terminated C string.
Expand All @@ -50,7 +54,10 @@ typedef enum
RCL_LOGGING_INTERFACE_PUBLIC
RCUTILS_WARN_UNUSED
rcl_logging_ret_t
rcl_logging_external_initialize(const char * config_file, rcutils_allocator_t allocator);
rcl_logging_external_initialize(
const char * file_name_prefix,
const char * config_file,
rcutils_allocator_t allocator);

/// Free the resources allocated for the external logging system.
/**
Expand Down
2 changes: 2 additions & 0 deletions rcl_logging_noop/src/rcl_logging_noop/rcl_logging_noop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,11 @@
#include <rcutils/allocator.h>

rcl_logging_ret_t rcl_logging_external_initialize(
const char * file_name_prefix,
const char * config_file,
rcutils_allocator_t allocator)
{
(void) file_name_prefix;
(void) config_file;
(void) allocator;
return RCL_LOGGING_RET_OK;
Expand Down
12 changes: 9 additions & 3 deletions rcl_logging_spdlog/src/rcl_logging_spdlog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include "rcutils/logging.h"
#include "rcutils/process.h"
#include "rcutils/snprintf.h"
#include "rcutils/strdup.h"
#include "rcutils/time.h"

#include "spdlog/spdlog.h"
Expand Down Expand Up @@ -95,6 +96,7 @@ get_should_use_old_flushing_behavior()
} // namespace

rcl_logging_ret_t rcl_logging_external_initialize(
const char * file_name_prefix,
const char * config_file,
rcutils_allocator_t allocator)
{
Expand Down Expand Up @@ -163,8 +165,13 @@ rcl_logging_ret_t rcl_logging_external_initialize(
}
int64_t ms_since_epoch = RCUTILS_NS_TO_MS(now);

// Get the program name.
char * basec = rcutils_get_executable_name(allocator);
bool file_name_provided = (nullptr != file_name_prefix) && (file_name_prefix[0] != '\0');
char * basec;
if (file_name_provided) {
basec = rcutils_strdup(file_name_prefix, allocator);
} else { // otherwise, get the program name.
basec = rcutils_get_executable_name(allocator);
}
if (basec == nullptr) {
// We couldn't get the program name, so get out of here without setting up
// logging.
Expand All @@ -175,7 +182,6 @@ rcl_logging_ret_t rcl_logging_external_initialize(
{
allocator.deallocate(basec, allocator.state);
});

char name_buffer[4096] = {0};
int print_ret = rcutils_snprintf(
name_buffer, sizeof(name_buffer),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ class LoggingBenchmarkPerformance : public PerformanceTest
void SetUp(benchmark::State & st)
{
rcl_logging_ret_t ret = rcl_logging_external_initialize(
nullptr,
nullptr,
rcutils_get_default_allocator());
if (ret != RCL_LOGGING_RET_OK) {
Expand Down Expand Up @@ -90,7 +91,7 @@ BENCHMARK_F(LoggingBenchmarkPerformance, log_level_miss)(benchmark::State & st)
BENCHMARK_F(PerformanceTest, logging_reinitialize)(benchmark::State & st)
{
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_logging_ret_t ret = rcl_logging_external_initialize(nullptr, allocator);
rcl_logging_ret_t ret = rcl_logging_external_initialize(nullptr, nullptr, allocator);
if (ret != RCL_LOGGING_RET_OK) {
st.SkipWithError(rcutils_get_error_string().str);
}
Expand All @@ -99,7 +100,7 @@ BENCHMARK_F(PerformanceTest, logging_reinitialize)(benchmark::State & st)

for (auto _ : st) {
RCUTILS_UNUSED(_);
ret = rcl_logging_external_initialize(nullptr, allocator);
ret = rcl_logging_external_initialize(nullptr, nullptr, allocator);
if (ret != RCL_LOGGING_RET_OK) {
st.SkipWithError(rcutils_get_error_string().str);
}
Expand All @@ -116,7 +117,7 @@ BENCHMARK_F(PerformanceTest, logging_initialize_shutdown)(benchmark::State & st)
rcutils_allocator_t allocator = rcutils_get_default_allocator();
for (auto _ : st) {
RCUTILS_UNUSED(_);
rcl_logging_ret_t ret = rcl_logging_external_initialize(nullptr, allocator);
rcl_logging_ret_t ret = rcl_logging_external_initialize(nullptr, nullptr, allocator);
if (ret != RCL_LOGGING_RET_OK) {
st.SkipWithError(rcutils_get_error_string().str);
}
Expand Down
18 changes: 12 additions & 6 deletions rcl_logging_spdlog/test/fixtures.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,14 +28,15 @@
#include "rcutils/env.h"
#include "rcutils/error_handling.h"
#include "rcutils/process.h"
#include "rcutils/strdup.h"
#include "rcutils/types/string_array.h"

#ifdef _WIN32
#define popen _popen
#define pclose _pclose
#define DIR_CMD "dir /B"
#define DIR_CMD "dir /B /O-D"
#else
#define DIR_CMD "ls -d"
#define DIR_CMD "ls -td"
#endif

class AllocatorTest : public ::testing::Test
Expand Down Expand Up @@ -80,11 +81,11 @@ class LoggingTest : public AllocatorTest
{
}

std::filesystem::path find_single_log()
std::filesystem::path find_single_log(const char * prefix)
{
std::filesystem::path log_dir = get_log_dir();
std::stringstream dir_command;
dir_command << DIR_CMD << " " << (log_dir / get_expected_log_prefix()).string() << "*";
dir_command << DIR_CMD << " " << (log_dir / get_expected_log_prefix(prefix)).string() << "*";

FILE * fp = popen(dir_command.str().c_str(), "r");
if (nullptr == fp) {
Expand All @@ -109,9 +110,14 @@ class LoggingTest : public AllocatorTest
}

private:
std::string get_expected_log_prefix()
std::string get_expected_log_prefix(const char * name)
{
char * exe_name = rcutils_get_executable_name(allocator);
char * exe_name;
if (name == nullptr || name[0] == '\0') {
exe_name = rcutils_get_executable_name(allocator);
} else {
exe_name = rcutils_strdup(name, allocator);
}
if (nullptr == exe_name) {
throw std::runtime_error("Failed to determine executable name");
}
Expand Down
59 changes: 44 additions & 15 deletions rcl_logging_spdlog/test/test_logging_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,11 +65,17 @@ class RestoreEnvVar
TEST_F(LoggingTest, init_invalid)
{
// Config files are not supported by spdlog
EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize("anything", allocator));
EXPECT_EQ(
RCL_LOGGING_RET_ERROR,
rcl_logging_external_initialize(nullptr, "anything", allocator));
rcutils_reset_error();
EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, bad_allocator));
EXPECT_EQ(
RCL_LOGGING_RET_ERROR,
rcl_logging_external_initialize("anything", nullptr, bad_allocator));
rcutils_reset_error();
EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, invalid_allocator));
EXPECT_EQ(
RCL_LOGGING_RET_ERROR,
rcl_logging_external_initialize(nullptr, nullptr, invalid_allocator));
rcutils_reset_error();
}

Expand All @@ -81,7 +87,7 @@ TEST_F(LoggingTest, init_failure)
// No home directory to write log to
ASSERT_EQ(true, rcutils_set_env("HOME", nullptr));
ASSERT_EQ(true, rcutils_set_env("USERPROFILE", nullptr));
EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, allocator));
EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, nullptr, allocator));
rcutils_reset_error();

// Force failure to create directories
Expand All @@ -92,26 +98,49 @@ TEST_F(LoggingTest, init_failure)
// ...fail to create .ros dir
std::filesystem::path ros_dir = fake_home / ".ros";
std::fstream(ros_dir.string(), std::ios_base::out).close();
EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, allocator));
EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, nullptr, allocator));
ASSERT_TRUE(std::filesystem::remove(ros_dir));

// ...fail to create .ros/log dir
ASSERT_TRUE(std::filesystem::create_directories(ros_dir));
std::filesystem::path ros_log_dir = ros_dir / "log";
std::fstream(ros_log_dir.string(), std::ios_base::out).close();
EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, allocator));
EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, nullptr, allocator));
ASSERT_TRUE(std::filesystem::remove(ros_log_dir));
ASSERT_TRUE(std::filesystem::remove(ros_dir));

ASSERT_TRUE(std::filesystem::remove(fake_home));
}

TEST_F(LoggingTest, log_file_name_prefix)
{
std::string log_file_path;
// executable name in default
{
ASSERT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_initialize(nullptr, nullptr, allocator));
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_shutdown());
EXPECT_NO_THROW(log_file_path = find_single_log(nullptr).string());
}
// falls back to executable name if not nullptr, but empty
{
ASSERT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_initialize("", nullptr, allocator));
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_shutdown());
EXPECT_NO_THROW(log_file_path = find_single_log(nullptr).string());
}
// specified by user application
{
ASSERT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_initialize("logger", nullptr, allocator));
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_shutdown());
EXPECT_NO_THROW(log_file_path = find_single_log("logger").string());
}
}

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));
ASSERT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_initialize(nullptr, nullptr, allocator));

std::stringstream expected_log;
for (int level : logger_levels) {
Expand All @@ -133,7 +162,7 @@ TEST_F(LoggingTest, init_old_flushing_behavior)

EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_shutdown());

std::string log_file_path = find_single_log().string();
std::string log_file_path = find_single_log(nullptr).string();
std::ifstream log_file(log_file_path);
std::stringstream actual_log;
actual_log << log_file.rdbuf();
Expand All @@ -147,7 +176,7 @@ 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));
ASSERT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_initialize(nullptr, nullptr, allocator));

std::stringstream expected_log;
for (int level : logger_levels) {
Expand All @@ -169,7 +198,7 @@ TEST_F(LoggingTest, init_explicit_new_flush_behavior)

EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_shutdown());

std::string log_file_path = find_single_log().string();
std::string log_file_path = find_single_log(nullptr).string();
std::ifstream log_file(log_file_path);
std::stringstream actual_log;
actual_log << log_file.rdbuf();
Expand All @@ -183,7 +212,7 @@ 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));
ASSERT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, nullptr, allocator));
std::string error_state_str = rcutils_get_error_string().str;
using ::testing::HasSubstr;
ASSERT_THAT(
Expand All @@ -194,10 +223,10 @@ TEST_F(LoggingTest, init_invalid_flush_setting)

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

// Make sure we can call initialize more than once
ASSERT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_initialize(nullptr, allocator));
ASSERT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_initialize(nullptr, nullptr, allocator));

std::stringstream expected_log;
for (int level : logger_levels) {
Expand All @@ -219,7 +248,7 @@ TEST_F(LoggingTest, full_cycle)

EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_shutdown());

std::string log_file_path = find_single_log().string();
std::string log_file_path = find_single_log(nullptr).string();
std::ifstream log_file(log_file_path);
std::stringstream actual_log;
actual_log << log_file.rdbuf();
Expand All @@ -232,7 +261,7 @@ TEST_F(LoggingTest, init_fini_maybe_fail_test)
{
RCUTILS_FAULT_INJECTION_TEST(
{
if (RCL_LOGGING_RET_OK == rcl_logging_external_initialize(nullptr, allocator)) {
if (RCL_LOGGING_RET_OK == rcl_logging_external_initialize(nullptr, nullptr, allocator)) {
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_external_shutdown());
} else {
EXPECT_TRUE(rcutils_error_is_set());
Expand Down

0 comments on commit fd629cf

Please sign in to comment.