diff --git a/rcl_logging_interface/test/test_get_logging_directory.cpp b/rcl_logging_interface/test/test_get_logging_directory.cpp index 971b020..f50edd1 100644 --- a/rcl_logging_interface/test/test_get_logging_directory.cpp +++ b/rcl_logging_interface/test/test_get_logging_directory.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include #include "gtest/gtest.h" -#include "rcpputils/filesystem_helper.hpp" #include "rcpputils/env.hpp" #include "rcutils/allocator.h" #include "rcutils/env.h" @@ -79,104 +79,104 @@ TEST(test_logging_directory, directory) directory = nullptr; // Default case without ROS_LOG_DIR or ROS_HOME being set (but with HOME) - rcpputils::fs::path fake_home("/fake_home_dir"); + std::filesystem::path fake_home("/fake_home_dir"); ASSERT_EQ(true, rcutils_set_env("HOME", fake_home.string().c_str())); ASSERT_EQ(true, rcutils_set_env("USERPROFILE", fake_home.string().c_str())); - rcpputils::fs::path default_dir = fake_home / ".ros" / "log"; + std::filesystem::path default_dir = fake_home / ".ros" / "log"; EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - EXPECT_STREQ(directory, default_dir.string().c_str()); + EXPECT_STREQ(directory, default_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; // Use $ROS_LOG_DIR if it is set const char * my_log_dir_raw = "/my/ros_log_dir"; - rcpputils::fs::path my_log_dir(my_log_dir_raw); + std::filesystem::path my_log_dir(my_log_dir_raw); ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", my_log_dir.string().c_str())); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - EXPECT_STREQ(directory, my_log_dir.string().c_str()); + EXPECT_STREQ(directory, my_log_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; // Make sure it converts path separators when necessary ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", my_log_dir_raw)); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - EXPECT_STREQ(directory, my_log_dir.string().c_str()); + EXPECT_STREQ(directory, my_log_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; // Setting ROS_HOME won't change anything since ROS_LOG_DIR is used first ASSERT_EQ(true, rcutils_set_env("ROS_HOME", "/this/wont/be/used")); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - EXPECT_STREQ(directory, my_log_dir.string().c_str()); + EXPECT_STREQ(directory, my_log_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; ASSERT_EQ(true, rcutils_set_env("ROS_HOME", nullptr)); // Empty is considered unset ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", "")); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - EXPECT_STREQ(directory, default_dir.string().c_str()); + EXPECT_STREQ(directory, default_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; // Make sure '~' is expanded to the home directory ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", "~/logdir")); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - rcpputils::fs::path fake_log_dir = fake_home / "logdir"; - EXPECT_STREQ(directory, fake_log_dir.string().c_str()); + std::filesystem::path fake_log_dir = fake_home / "logdir"; + EXPECT_STREQ(directory, fake_log_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; // But it should only be expanded if it's at the beginning - rcpputils::fs::path prefixed_fake_log_dir("/prefix/~/logdir"); + std::filesystem::path prefixed_fake_log_dir("/prefix/~/logdir"); ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", prefixed_fake_log_dir.string().c_str())); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - EXPECT_STREQ(directory, prefixed_fake_log_dir.string().c_str()); + EXPECT_STREQ(directory, prefixed_fake_log_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", "~")); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - EXPECT_STREQ(directory, fake_home.string().c_str()); + EXPECT_STREQ(directory, fake_home.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; - rcpputils::fs::path home_trailing_slash(fake_home.string() + "/"); + std::filesystem::path home_trailing_slash(fake_home.string() + "/"); ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", "~/")); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - EXPECT_STREQ(directory, home_trailing_slash.string().c_str()); + EXPECT_STREQ(directory, home_trailing_slash.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", nullptr)); // Without ROS_LOG_DIR, use $ROS_HOME/log - rcpputils::fs::path fake_ros_home = fake_home / ".fakeroshome"; + std::filesystem::path fake_ros_home = fake_home / ".fakeroshome"; ASSERT_EQ(true, rcutils_set_env("ROS_HOME", fake_ros_home.string().c_str())); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - rcpputils::fs::path fake_ros_home_log_dir = fake_ros_home / "log"; - EXPECT_STREQ(directory, fake_ros_home_log_dir.string().c_str()); + std::filesystem::path fake_ros_home_log_dir = fake_ros_home / "log"; + EXPECT_STREQ(directory, fake_ros_home_log_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; // Make sure it converts path separators when necessary const char * my_ros_home_raw = "/my/ros/home"; ASSERT_EQ(true, rcutils_set_env("ROS_HOME", my_ros_home_raw)); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - rcpputils::fs::path my_ros_home_log_dir = rcpputils::fs::path(my_ros_home_raw) / "log"; - EXPECT_STREQ(directory, my_ros_home_log_dir.string().c_str()); + std::filesystem::path my_ros_home_log_dir = std::filesystem::path(my_ros_home_raw) / "log"; + EXPECT_STREQ(directory, my_ros_home_log_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; // Empty is considered unset ASSERT_EQ(true, rcutils_set_env("ROS_HOME", "")); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - EXPECT_STREQ(directory, default_dir.string().c_str()); + EXPECT_STREQ(directory, default_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; // Make sure '~' is expanded to the home directory ASSERT_EQ(true, rcutils_set_env("ROS_HOME", "~/.fakeroshome")); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - EXPECT_STREQ(directory, fake_ros_home_log_dir.string().c_str()); + EXPECT_STREQ(directory, fake_ros_home_log_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; // But it should only be expanded if it's at the beginning - rcpputils::fs::path prefixed_fake_ros_home("/prefix/~/.fakeroshome"); - rcpputils::fs::path prefixed_fake_ros_home_log_dir = prefixed_fake_ros_home / "log"; + std::filesystem::path prefixed_fake_ros_home("/prefix/~/.fakeroshome"); + std::filesystem::path prefixed_fake_ros_home_log_dir = prefixed_fake_ros_home / "log"; ASSERT_EQ(true, rcutils_set_env("ROS_HOME", prefixed_fake_ros_home.string().c_str())); EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); - EXPECT_STREQ(directory, prefixed_fake_ros_home_log_dir.string().c_str()); + EXPECT_STREQ(directory, prefixed_fake_ros_home_log_dir.make_preferred().string().c_str()); allocator.deallocate(directory, allocator.state); directory = nullptr; diff --git a/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp b/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp index 9369c5c..66b6c1c 100644 --- a/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp +++ b/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp @@ -15,13 +15,16 @@ #include #include #include +#include #include #include #include +#include #include -#include "rcpputils/filesystem_helper.hpp" #include "rcpputils/env.hpp" +#include "rcpputils/scope_exit.hpp" + #include "rcutils/allocator.h" #include "rcutils/logging.h" #include "rcutils/process.h" @@ -131,12 +134,21 @@ rcl_logging_ret_t rcl_logging_external_initialize( RCUTILS_SET_ERROR_MSG("Failed to get logging directory"); return dir_ret; } - - // SPDLOG doesn't automatically create the log directories, so create them - rcpputils::fs::path logdir_path(logdir); - if (!rcpputils::fs::create_directories(logdir_path)) { - RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING("Failed to create log directory: %s", logdir); + RCPPUTILS_SCOPE_EXIT( + { allocator.deallocate(logdir, allocator.state); + }); + + std::error_code ec; + std::filesystem::path logdir_path(logdir); + + std::filesystem::create_directories(logdir_path, ec); + // create_directories returns true if it created the directory, and false if it did not. + // This behavior is maintained regardless of whether an error occurred. Since we don't + // actually care whether the directory was created, we only check for errors. + if (ec.value() != 0) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Failed to create log directory '%s': %d", logdir, ec.value()); return RCL_LOGGING_RET_ERROR; } @@ -144,7 +156,6 @@ rcl_logging_ret_t rcl_logging_external_initialize( rcutils_time_point_value_t now; rcutils_ret_t ret = rcutils_system_time_now(&now); if (ret != RCUTILS_RET_OK) { - allocator.deallocate(logdir, allocator.state); // We couldn't get the system time, so get out of here without setting up // logging. We don't need to call RCUTILS_SET_ERROR_MSG either since // rcutils_system_time_now() already did it. @@ -155,20 +166,21 @@ rcl_logging_ret_t rcl_logging_external_initialize( // Get the program name. char * basec = rcutils_get_executable_name(allocator); if (basec == nullptr) { - allocator.deallocate(logdir, allocator.state); // We couldn't get the program name, so get out of here without setting up // logging. RCUTILS_SET_ERROR_MSG("Failed to get the executable name"); return RCL_LOGGING_RET_ERROR; } + RCPPUTILS_SCOPE_EXIT( + { + allocator.deallocate(basec, allocator.state); + }); char name_buffer[4096] = {0}; int print_ret = rcutils_snprintf( name_buffer, sizeof(name_buffer), "%s/%s_%i_%" PRId64 ".log", logdir, basec, rcutils_get_pid(), ms_since_epoch); - allocator.deallocate(logdir, allocator.state); - allocator.deallocate(basec, allocator.state); if (print_ret < 0) { RCUTILS_SET_ERROR_MSG("Failed to create log file name string"); return RCL_LOGGING_RET_ERROR; diff --git a/rcl_logging_spdlog/test/fixtures.hpp b/rcl_logging_spdlog/test/fixtures.hpp index 85697f9..84e977d 100644 --- a/rcl_logging_spdlog/test/fixtures.hpp +++ b/rcl_logging_spdlog/test/fixtures.hpp @@ -20,10 +20,10 @@ # include // MAX_PATH #endif #include +#include #include "gtest/gtest.h" -#include "rcpputils/filesystem_helper.hpp" #include "rcutils/allocator.h" #include "rcutils/env.h" #include "rcutils/error_handling.h" @@ -38,8 +38,6 @@ #define DIR_CMD "ls -d" #endif -namespace fs = rcpputils::fs; - class AllocatorTest : public ::testing::Test { public: @@ -82,9 +80,9 @@ class LoggingTest : public AllocatorTest { } - fs::path find_single_log() + std::filesystem::path find_single_log() { - fs::path log_dir = get_log_dir(); + std::filesystem::path log_dir = get_log_dir(); std::stringstream dir_command; dir_command << DIR_CMD << " " << (log_dir / get_expected_log_prefix()).string() << "*"; @@ -105,7 +103,7 @@ class LoggingTest : public AllocatorTest } std::string line(raw_line); - fs::path line_path(line.substr(0, line.find_last_not_of(" \t\r\n") + 1)); + std::filesystem::path line_path(line.substr(0, line.find_last_not_of(" \t\r\n") + 1)); // This should be changed once ros2/rcpputils#68 is resolved return line_path.is_absolute() ? line_path : log_dir / line_path; } @@ -123,9 +121,9 @@ class LoggingTest : public AllocatorTest return prefix.str(); } - fs::path get_log_dir() + std::filesystem::path get_log_dir() { - return fs::path(rcutils_get_home_dir()) / ".ros" / "log"; + return std::filesystem::path(rcutils_get_home_dir()) / ".ros" / "log"; } }; diff --git a/rcl_logging_spdlog/test/test_logging_interface.cpp b/rcl_logging_spdlog/test/test_logging_interface.cpp index 3956787..b5d9b15 100644 --- a/rcl_logging_spdlog/test/test_logging_interface.cpp +++ b/rcl_logging_spdlog/test/test_logging_interface.cpp @@ -13,12 +13,12 @@ // limitations under the License. #include +#include #include #include #include "gmock/gmock.h" -#include "rcpputils/filesystem_helper.hpp" #include "rcpputils/env.hpp" #include "rcutils/allocator.h" #include "rcutils/env.h" @@ -85,25 +85,25 @@ TEST_F(LoggingTest, init_failure) rcutils_reset_error(); // Force failure to create directories - rcpputils::fs::path fake_home = rcpputils::fs::current_path() / "fake_home_dir"; - ASSERT_TRUE(rcpputils::fs::create_directories(fake_home)); + std::filesystem::path fake_home = std::filesystem::current_path() / "fake_home_dir"; + ASSERT_TRUE(std::filesystem::create_directories(fake_home)); ASSERT_EQ(true, rcutils_set_env("HOME", fake_home.string().c_str())); // ...fail to create .ros dir - rcpputils::fs::path ros_dir = fake_home / ".ros"; + 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)); - ASSERT_TRUE(rcpputils::fs::remove(ros_dir)); + ASSERT_TRUE(std::filesystem::remove(ros_dir)); // ...fail to create .ros/log dir - ASSERT_TRUE(rcpputils::fs::create_directories(ros_dir)); - rcpputils::fs::path ros_log_dir = ros_dir / "log"; + 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)); - ASSERT_TRUE(rcpputils::fs::remove(ros_log_dir)); - ASSERT_TRUE(rcpputils::fs::remove(ros_dir)); + ASSERT_TRUE(std::filesystem::remove(ros_log_dir)); + ASSERT_TRUE(std::filesystem::remove(ros_dir)); - ASSERT_TRUE(rcpputils::fs::remove(fake_home)); + ASSERT_TRUE(std::filesystem::remove(fake_home)); } TEST_F(LoggingTest, init_old_flushing_behavior)