diff --git a/rcl_logging_spdlog/CMakeLists.txt b/rcl_logging_spdlog/CMakeLists.txt index d3e25c5..d6b31e2 100644 --- a/rcl_logging_spdlog/CMakeLists.txt +++ b/rcl_logging_spdlog/CMakeLists.txt @@ -15,6 +15,7 @@ find_package(ament_cmake_ros REQUIRED) find_package(rcutils REQUIRED) find_package(spdlog_vendor REQUIRED) # Provides spdlog 1.3.1 on platforms without it. find_package(spdlog REQUIRED) +find_package(rcpputils REQUIRED) if(NOT WIN32) add_compile_options(-Wall -Wextra -Wpedantic) @@ -29,6 +30,7 @@ target_link_libraries(${PROJECT_NAME} spdlog::spdlog) ament_target_dependencies(${PROJECT_NAME} rcutils spdlog + rcpputils ) target_compile_definitions(${PROJECT_NAME} PRIVATE "RCL_LOGGING_BUILDING_DLL") diff --git a/rcl_logging_spdlog/include/rcl_logging_spdlog/logging_interface.h b/rcl_logging_spdlog/include/rcl_logging_spdlog/logging_interface.h index b1c08d0..d422f04 100644 --- a/rcl_logging_spdlog/include/rcl_logging_spdlog/logging_interface.h +++ b/rcl_logging_spdlog/include/rcl_logging_spdlog/logging_interface.h @@ -76,6 +76,29 @@ RCL_LOGGING_PUBLIC RCUTILS_WARN_UNUSED rcl_logging_ret_t rcl_logging_external_set_logger_level(const char * name, int level); +/// Get the logging directory. +/** + * Uses various environment variables to construct a logging directory path. + * + * Use $ROS_LOG_DIR if ROS_LOG_DIR is set and not empty. + * Otherwise, use $ROS_HOME/log, using ~/.ros for ROS_HOME if not set or if empty. + * + * It also expands an initial '~' to the current user's home directory, + * and converts the path separator if necessary. + * + * If successful, the directory C string should be deallocated using the given allocator when it is + * no longer needed. + * + * \param[in] allocator The allocator to use for memory allocation. + * \param[out] directory The C string pointer at which to write the directory path. + * Only meaningful if the call is successful. Must not be nullptr and must point to nullptr. + * \return RCL_LOGGING_RET_OK if successful, or + * \return RCL_LOGGING_RET_INVALID_ARGUMENT if any arguments are invalid, or + * \return RCL_LOGGING_RET_ERROR if an unspecified error occurs. + */ +RCL_LOGGING_PUBLIC +rcl_logging_ret_t +rcl_logging_get_logging_directory(rcutils_allocator_t allocator, char ** directory); #ifdef __cplusplus } /* extern "C" */ diff --git a/rcl_logging_spdlog/package.xml b/rcl_logging_spdlog/package.xml index cb4d0f9..5eef78a 100644 --- a/rcl_logging_spdlog/package.xml +++ b/rcl_logging_spdlog/package.xml @@ -14,6 +14,7 @@ spdlog rcutils + rcpputils spdlog_vendor spdlog @@ -21,7 +22,6 @@ ament_lint_auto ament_lint_common performance_test_fixture - rcpputils rcl_logging_packages diff --git a/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp b/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp index 86089e9..fb4ea0f 100644 --- a/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp +++ b/rcl_logging_spdlog/src/rcl_logging_spdlog.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include #include @@ -19,6 +20,8 @@ #include #include #include +#include +#include #include #include @@ -82,36 +85,20 @@ rcl_logging_ret_t rcl_logging_external_initialize( // To be compatible with ROS 1, we construct a default filename of // the form ~/.ros/log/__.log - // First get the home directory. - const char * homedir = rcutils_get_home_dir(); - if (homedir == nullptr) { - // We couldn't get the home directory; it is not really going to be - // possible to do logging properly, so get out of here without setting - // up logging. - RCUTILS_SET_ERROR_MSG("Failed to get users home directory"); - return RCL_LOGGING_RET_ERROR; - } - - // SPDLOG doesn't automatically create the log directories, so make them - // by hand here. - char name_buffer[4096] = {0}; - int print_ret = rcutils_snprintf(name_buffer, sizeof(name_buffer), "%s/.ros", homedir); - if (print_ret < 0) { - RCUTILS_SET_ERROR_MSG("Failed to create home directory string"); - return RCL_LOGGING_RET_ERROR; - } - if (!rcutils_mkdir(name_buffer)) { - RCUTILS_SET_ERROR_MSG("Failed to create user .ros directory"); + char * logdir = nullptr; + rcl_logging_ret_t dir_ret = rcl_logging_get_logging_directory(allocator, &logdir); + if (RCL_LOGGING_RET_OK != dir_ret) { + // We couldn't get the log directory, so get out of here without setting up + // logging. + RCUTILS_SET_ERROR_MSG("Failed to get logging directory"); return RCL_LOGGING_RET_ERROR; } - print_ret = rcutils_snprintf(name_buffer, sizeof(name_buffer), "%s/.ros/log", homedir); - if (print_ret < 0) { - RCUTILS_SET_ERROR_MSG("Failed to create log directory string"); - return RCL_LOGGING_RET_ERROR; - } - if (!rcutils_mkdir(name_buffer)) { - RCUTILS_SET_ERROR_MSG("Failed to create user log directory"); + // 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); + allocator.deallocate(logdir, allocator.state); return RCL_LOGGING_RET_ERROR; } @@ -135,10 +122,12 @@ rcl_logging_ret_t rcl_logging_external_initialize( return RCL_LOGGING_RET_ERROR; } - print_ret = rcutils_snprintf( + char name_buffer[4096] = {0}; + int print_ret = rcutils_snprintf( name_buffer, sizeof(name_buffer), - "%s/.ros/log/%s_%i_%" PRId64 ".log", homedir, + "%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"); @@ -175,6 +164,101 @@ rcl_logging_ret_t rcl_logging_external_set_logger_level(const char * name, int l return RCL_LOGGING_RET_OK; } + +static char * +rcl_expand_user(const char * path, rcutils_allocator_t allocator) +{ + if (NULL == path) { + return NULL; + } + + if ('~' != path[0]) { + return rcutils_strdup(path, allocator); + } + + const char * homedir = rcutils_get_home_dir(); + if (NULL == homedir) { + return NULL; + } + return rcutils_format_string_limit( + allocator, + strlen(homedir) + strlen(path), + "%s%s", + homedir, + path + 1); +} + +rcl_logging_ret_t +rcl_logging_get_logging_directory(rcutils_allocator_t allocator, char ** directory) +{ + if (NULL == directory) { + RCUTILS_SET_ERROR_MSG("directory argument must not be null"); + return RCL_LOGGING_RET_ERROR; + } + if (NULL != *directory) { + RCUTILS_SET_ERROR_MSG("directory argument must point to null"); + return RCL_LOGGING_RET_ERROR; + } + + const char * log_dir_env; + const char * err = rcutils_get_env("ROS_LOG_DIR", &log_dir_env); + if (NULL != err) { + RCUTILS_SET_ERROR_MSG("rcutils_get_env failed"); + return RCL_LOGGING_RET_ERROR; + } + if ('\0' != *log_dir_env) { + *directory = rcutils_strdup(log_dir_env, allocator); + if (NULL == *directory) { + RCUTILS_SET_ERROR_MSG("rcutils_strdup failed"); + return RCL_LOGGING_RET_ERROR; + } + } else { + const char * ros_home_dir_env; + err = rcutils_get_env("ROS_HOME", &ros_home_dir_env); + if (NULL != err) { + RCUTILS_SET_ERROR_MSG("rcutils_get_env failed"); + return RCL_LOGGING_RET_ERROR; + } + char * ros_home_dir; + if ('\0' == *ros_home_dir_env) { + ros_home_dir = rcutils_join_path("~", ".ros", allocator); + if (NULL == ros_home_dir) { + RCUTILS_SET_ERROR_MSG("rcutils_join_path failed"); + return RCL_LOGGING_RET_ERROR; + } + } else { + ros_home_dir = rcutils_strdup(ros_home_dir_env, allocator); + if (NULL == ros_home_dir) { + RCUTILS_SET_ERROR_MSG("rcutils_strdup failed"); + return RCL_LOGGING_RET_ERROR; + } + } + *directory = rcutils_join_path(ros_home_dir, "log", allocator); + allocator.deallocate(ros_home_dir, allocator.state); + if (NULL == *directory) { + RCUTILS_SET_ERROR_MSG("rcutils_join_path failed"); + return RCL_LOGGING_RET_ERROR; + } + } + + char * directory_maybe_not_expanded = *directory; + *directory = rcl_expand_user(directory_maybe_not_expanded, allocator); + allocator.deallocate(directory_maybe_not_expanded, allocator.state); + if (NULL == *directory) { + RCUTILS_SET_ERROR_MSG("rcutils_expand_user failed"); + return RCL_LOGGING_RET_ERROR; + } + + char * directory_maybe_not_native = *directory; + *directory = rcutils_to_native_path(directory_maybe_not_native, allocator); + allocator.deallocate(directory_maybe_not_native, allocator.state); + if (NULL == *directory) { + RCUTILS_SET_ERROR_MSG("rcutils_to_native_path failed"); + return RCL_LOGGING_RET_ERROR; + } + return RCL_LOGGING_RET_OK; +} + #ifdef __cplusplus } /* extern "C" */ #endif diff --git a/rcl_logging_spdlog/test/test_logging_interface.cpp b/rcl_logging_spdlog/test/test_logging_interface.cpp index c68b9b8..a325898 100644 --- a/rcl_logging_spdlog/test/test_logging_interface.cpp +++ b/rcl_logging_spdlog/test/test_logging_interface.cpp @@ -66,27 +66,6 @@ class RestoreEnvVar const std::string value_; }; -// TODO(cottsay): Remove when ros2/rcpputils#63 is resolved -static fs::path current_path() -{ -#ifdef _WIN32 -#ifdef UNICODE -#error "rcpputils::fs does not support Unicode paths" -#endif - char cwd[MAX_PATH]; - if (nullptr == _getcwd(cwd, MAX_PATH)) { -#else - char cwd[PATH_MAX]; - if (nullptr == getcwd(cwd, PATH_MAX)) { -#endif - std::error_code ec{errno, std::system_category()}; - errno = 0; - throw std::system_error{ec, "cannot get current working directory"}; - } - - return fs::path(cwd); -} - TEST_F(LoggingTest, init_invalid) { // Config files are not supported by spdlog @@ -98,37 +77,139 @@ TEST_F(LoggingTest, init_invalid) rcutils_reset_error(); } -TEST_F(LoggingTest, init_failure) +TEST_F(LoggingTest, directory) { RestoreEnvVar home_var("HOME"); RestoreEnvVar userprofile_var("USERPROFILE"); - - // 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(2, rcl_logging_external_initialize(nullptr, allocator)); + ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", nullptr)); + ASSERT_EQ(true, rcutils_set_env("ROS_HOME", nullptr)); + + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + + // Invalid argument if given a nullptr + EXPECT_EQ( + RCL_LOGGING_RET_ERROR, rcl_logging_get_logging_directory(allocator, nullptr)); + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + // Invalid argument if the C string is not nullptr + char * could_leak = const_cast("/could/be/leaked"); + EXPECT_EQ( + RCL_LOGGING_RET_ERROR, rcl_logging_get_logging_directory(allocator, &could_leak)); + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + + // Fails without any relevant env vars at all (HOME included) + char * directory = nullptr; + EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_get_logging_directory(allocator, &directory)); + EXPECT_TRUE(rcutils_error_is_set()); rcutils_reset_error(); + directory = nullptr; - // Force failure to create directories - fs::path fake_home = current_path() / "fake_home_dir"; - ASSERT_TRUE(fs::create_directories(fake_home)); + // Default case without ROS_LOG_DIR or ROS_HOME being set (but with HOME) + rcpputils::fs::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"; + EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory)); + EXPECT_STREQ(directory, default_dir.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); + 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()); + 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()); + 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()); + 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()); + 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()); + 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"); + 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()); + 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()); + allocator.deallocate(directory, allocator.state); + directory = nullptr; + rcpputils::fs::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()); + 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"; + 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()); + 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()); + 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()); + 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()); + 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"; + 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()); + allocator.deallocate(directory, allocator.state); + directory = nullptr; - // ...fail to create .ros dir - fs::path ros_dir = fake_home / ".ros"; - std::fstream(ros_dir.string(), std::ios_base::out).close(); - EXPECT_EQ(2, rcl_logging_external_initialize(nullptr, allocator)); - ASSERT_TRUE(fs::remove(ros_dir)); - - // ...fail to create .ros/log dir - ASSERT_TRUE(fs::create_directories(ros_dir)); - fs::path ros_log_dir = ros_dir / "log"; - std::fstream(ros_log_dir.string(), std::ios_base::out).close(); - EXPECT_EQ(2, rcl_logging_external_initialize(nullptr, allocator)); - ASSERT_TRUE(fs::remove(ros_log_dir)); - ASSERT_TRUE(fs::remove(ros_dir)); - - ASSERT_TRUE(fs::remove(fake_home)); + ASSERT_EQ(true, rcutils_set_env("ROS_HOME", nullptr)); } TEST_F(LoggingTest, full_cycle)