Skip to content

Commit 1af4e49

Browse files
authored
Migrate to std::filesystem (#104)
* Migrate to std::filesystem Signed-off-by: Kenta Yonekura <[email protected]> Signed-off-by: Chris Lalancette <[email protected]>
1 parent 014239d commit 1af4e49

File tree

4 files changed

+64
-54
lines changed

4 files changed

+64
-54
lines changed

rcl_logging_interface/test/test_get_logging_directory.cpp

Lines changed: 26 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -12,12 +12,12 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include <filesystem>
1516
#include <iostream>
1617
#include <string>
1718

1819
#include "gtest/gtest.h"
1920

20-
#include "rcpputils/filesystem_helper.hpp"
2121
#include "rcpputils/env.hpp"
2222
#include "rcutils/allocator.h"
2323
#include "rcutils/env.h"
@@ -79,104 +79,104 @@ TEST(test_logging_directory, directory)
7979
directory = nullptr;
8080

8181
// Default case without ROS_LOG_DIR or ROS_HOME being set (but with HOME)
82-
rcpputils::fs::path fake_home("/fake_home_dir");
82+
std::filesystem::path fake_home("/fake_home_dir");
8383
ASSERT_EQ(true, rcutils_set_env("HOME", fake_home.string().c_str()));
8484
ASSERT_EQ(true, rcutils_set_env("USERPROFILE", fake_home.string().c_str()));
85-
rcpputils::fs::path default_dir = fake_home / ".ros" / "log";
85+
std::filesystem::path default_dir = fake_home / ".ros" / "log";
8686
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
87-
EXPECT_STREQ(directory, default_dir.string().c_str());
87+
EXPECT_STREQ(directory, default_dir.make_preferred().string().c_str());
8888
allocator.deallocate(directory, allocator.state);
8989
directory = nullptr;
9090

9191
// Use $ROS_LOG_DIR if it is set
9292
const char * my_log_dir_raw = "/my/ros_log_dir";
93-
rcpputils::fs::path my_log_dir(my_log_dir_raw);
93+
std::filesystem::path my_log_dir(my_log_dir_raw);
9494
ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", my_log_dir.string().c_str()));
9595
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
96-
EXPECT_STREQ(directory, my_log_dir.string().c_str());
96+
EXPECT_STREQ(directory, my_log_dir.make_preferred().string().c_str());
9797
allocator.deallocate(directory, allocator.state);
9898
directory = nullptr;
9999
// Make sure it converts path separators when necessary
100100
ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", my_log_dir_raw));
101101
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
102-
EXPECT_STREQ(directory, my_log_dir.string().c_str());
102+
EXPECT_STREQ(directory, my_log_dir.make_preferred().string().c_str());
103103
allocator.deallocate(directory, allocator.state);
104104
directory = nullptr;
105105
// Setting ROS_HOME won't change anything since ROS_LOG_DIR is used first
106106
ASSERT_EQ(true, rcutils_set_env("ROS_HOME", "/this/wont/be/used"));
107107
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
108-
EXPECT_STREQ(directory, my_log_dir.string().c_str());
108+
EXPECT_STREQ(directory, my_log_dir.make_preferred().string().c_str());
109109
allocator.deallocate(directory, allocator.state);
110110
directory = nullptr;
111111
ASSERT_EQ(true, rcutils_set_env("ROS_HOME", nullptr));
112112
// Empty is considered unset
113113
ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", ""));
114114
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
115-
EXPECT_STREQ(directory, default_dir.string().c_str());
115+
EXPECT_STREQ(directory, default_dir.make_preferred().string().c_str());
116116
allocator.deallocate(directory, allocator.state);
117117
directory = nullptr;
118118
// Make sure '~' is expanded to the home directory
119119
ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", "~/logdir"));
120120
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
121-
rcpputils::fs::path fake_log_dir = fake_home / "logdir";
122-
EXPECT_STREQ(directory, fake_log_dir.string().c_str());
121+
std::filesystem::path fake_log_dir = fake_home / "logdir";
122+
EXPECT_STREQ(directory, fake_log_dir.make_preferred().string().c_str());
123123
allocator.deallocate(directory, allocator.state);
124124
directory = nullptr;
125125
// But it should only be expanded if it's at the beginning
126-
rcpputils::fs::path prefixed_fake_log_dir("/prefix/~/logdir");
126+
std::filesystem::path prefixed_fake_log_dir("/prefix/~/logdir");
127127
ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", prefixed_fake_log_dir.string().c_str()));
128128
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
129-
EXPECT_STREQ(directory, prefixed_fake_log_dir.string().c_str());
129+
EXPECT_STREQ(directory, prefixed_fake_log_dir.make_preferred().string().c_str());
130130
allocator.deallocate(directory, allocator.state);
131131
directory = nullptr;
132132
ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", "~"));
133133
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
134-
EXPECT_STREQ(directory, fake_home.string().c_str());
134+
EXPECT_STREQ(directory, fake_home.make_preferred().string().c_str());
135135
allocator.deallocate(directory, allocator.state);
136136
directory = nullptr;
137-
rcpputils::fs::path home_trailing_slash(fake_home.string() + "/");
137+
std::filesystem::path home_trailing_slash(fake_home.string() + "/");
138138
ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", "~/"));
139139
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
140-
EXPECT_STREQ(directory, home_trailing_slash.string().c_str());
140+
EXPECT_STREQ(directory, home_trailing_slash.make_preferred().string().c_str());
141141
allocator.deallocate(directory, allocator.state);
142142
directory = nullptr;
143143

144144
ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", nullptr));
145145

146146
// Without ROS_LOG_DIR, use $ROS_HOME/log
147-
rcpputils::fs::path fake_ros_home = fake_home / ".fakeroshome";
147+
std::filesystem::path fake_ros_home = fake_home / ".fakeroshome";
148148
ASSERT_EQ(true, rcutils_set_env("ROS_HOME", fake_ros_home.string().c_str()));
149149
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
150-
rcpputils::fs::path fake_ros_home_log_dir = fake_ros_home / "log";
151-
EXPECT_STREQ(directory, fake_ros_home_log_dir.string().c_str());
150+
std::filesystem::path fake_ros_home_log_dir = fake_ros_home / "log";
151+
EXPECT_STREQ(directory, fake_ros_home_log_dir.make_preferred().string().c_str());
152152
allocator.deallocate(directory, allocator.state);
153153
directory = nullptr;
154154
// Make sure it converts path separators when necessary
155155
const char * my_ros_home_raw = "/my/ros/home";
156156
ASSERT_EQ(true, rcutils_set_env("ROS_HOME", my_ros_home_raw));
157157
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
158-
rcpputils::fs::path my_ros_home_log_dir = rcpputils::fs::path(my_ros_home_raw) / "log";
159-
EXPECT_STREQ(directory, my_ros_home_log_dir.string().c_str());
158+
std::filesystem::path my_ros_home_log_dir = std::filesystem::path(my_ros_home_raw) / "log";
159+
EXPECT_STREQ(directory, my_ros_home_log_dir.make_preferred().string().c_str());
160160
allocator.deallocate(directory, allocator.state);
161161
directory = nullptr;
162162
// Empty is considered unset
163163
ASSERT_EQ(true, rcutils_set_env("ROS_HOME", ""));
164164
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
165-
EXPECT_STREQ(directory, default_dir.string().c_str());
165+
EXPECT_STREQ(directory, default_dir.make_preferred().string().c_str());
166166
allocator.deallocate(directory, allocator.state);
167167
directory = nullptr;
168168
// Make sure '~' is expanded to the home directory
169169
ASSERT_EQ(true, rcutils_set_env("ROS_HOME", "~/.fakeroshome"));
170170
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
171-
EXPECT_STREQ(directory, fake_ros_home_log_dir.string().c_str());
171+
EXPECT_STREQ(directory, fake_ros_home_log_dir.make_preferred().string().c_str());
172172
allocator.deallocate(directory, allocator.state);
173173
directory = nullptr;
174174
// But it should only be expanded if it's at the beginning
175-
rcpputils::fs::path prefixed_fake_ros_home("/prefix/~/.fakeroshome");
176-
rcpputils::fs::path prefixed_fake_ros_home_log_dir = prefixed_fake_ros_home / "log";
175+
std::filesystem::path prefixed_fake_ros_home("/prefix/~/.fakeroshome");
176+
std::filesystem::path prefixed_fake_ros_home_log_dir = prefixed_fake_ros_home / "log";
177177
ASSERT_EQ(true, rcutils_set_env("ROS_HOME", prefixed_fake_ros_home.string().c_str()));
178178
EXPECT_EQ(RCL_LOGGING_RET_OK, rcl_logging_get_logging_directory(allocator, &directory));
179-
EXPECT_STREQ(directory, prefixed_fake_ros_home_log_dir.string().c_str());
179+
EXPECT_STREQ(directory, prefixed_fake_ros_home_log_dir.make_preferred().string().c_str());
180180
allocator.deallocate(directory, allocator.state);
181181
directory = nullptr;
182182

rcl_logging_spdlog/src/rcl_logging_spdlog.cpp

Lines changed: 22 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -15,13 +15,16 @@
1515
#include <cerrno>
1616
#include <chrono>
1717
#include <cinttypes>
18+
#include <filesystem>
1819
#include <memory>
1920
#include <mutex>
2021
#include <string>
22+
#include <system_error>
2123
#include <utility>
2224

23-
#include "rcpputils/filesystem_helper.hpp"
2425
#include "rcpputils/env.hpp"
26+
#include "rcpputils/scope_exit.hpp"
27+
2528
#include "rcutils/allocator.h"
2629
#include "rcutils/logging.h"
2730
#include "rcutils/process.h"
@@ -131,20 +134,28 @@ rcl_logging_ret_t rcl_logging_external_initialize(
131134
RCUTILS_SET_ERROR_MSG("Failed to get logging directory");
132135
return dir_ret;
133136
}
134-
135-
// SPDLOG doesn't automatically create the log directories, so create them
136-
rcpputils::fs::path logdir_path(logdir);
137-
if (!rcpputils::fs::create_directories(logdir_path)) {
138-
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING("Failed to create log directory: %s", logdir);
137+
RCPPUTILS_SCOPE_EXIT(
138+
{
139139
allocator.deallocate(logdir, allocator.state);
140+
});
141+
142+
std::error_code ec;
143+
std::filesystem::path logdir_path(logdir);
144+
145+
std::filesystem::create_directories(logdir_path, ec);
146+
// create_directories returns true if it created the directory, and false if it did not.
147+
// This behavior is maintained regardless of whether an error occurred. Since we don't
148+
// actually care whether the directory was created, we only check for errors.
149+
if (ec.value() != 0) {
150+
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
151+
"Failed to create log directory '%s': %d", logdir, ec.value());
140152
return RCL_LOGGING_RET_ERROR;
141153
}
142154

143155
// Now get the milliseconds since the epoch in the local timezone.
144156
rcutils_time_point_value_t now;
145157
rcutils_ret_t ret = rcutils_system_time_now(&now);
146158
if (ret != RCUTILS_RET_OK) {
147-
allocator.deallocate(logdir, allocator.state);
148159
// We couldn't get the system time, so get out of here without setting up
149160
// logging. We don't need to call RCUTILS_SET_ERROR_MSG either since
150161
// rcutils_system_time_now() already did it.
@@ -155,20 +166,21 @@ rcl_logging_ret_t rcl_logging_external_initialize(
155166
// Get the program name.
156167
char * basec = rcutils_get_executable_name(allocator);
157168
if (basec == nullptr) {
158-
allocator.deallocate(logdir, allocator.state);
159169
// We couldn't get the program name, so get out of here without setting up
160170
// logging.
161171
RCUTILS_SET_ERROR_MSG("Failed to get the executable name");
162172
return RCL_LOGGING_RET_ERROR;
163173
}
174+
RCPPUTILS_SCOPE_EXIT(
175+
{
176+
allocator.deallocate(basec, allocator.state);
177+
});
164178

165179
char name_buffer[4096] = {0};
166180
int print_ret = rcutils_snprintf(
167181
name_buffer, sizeof(name_buffer),
168182
"%s/%s_%i_%" PRId64 ".log", logdir,
169183
basec, rcutils_get_pid(), ms_since_epoch);
170-
allocator.deallocate(logdir, allocator.state);
171-
allocator.deallocate(basec, allocator.state);
172184
if (print_ret < 0) {
173185
RCUTILS_SET_ERROR_MSG("Failed to create log file name string");
174186
return RCL_LOGGING_RET_ERROR;

rcl_logging_spdlog/test/fixtures.hpp

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -20,10 +20,10 @@
2020
# include <windows.h> // MAX_PATH
2121
#endif
2222
#include <string>
23+
#include <filesystem>
2324

2425
#include "gtest/gtest.h"
2526

26-
#include "rcpputils/filesystem_helper.hpp"
2727
#include "rcutils/allocator.h"
2828
#include "rcutils/env.h"
2929
#include "rcutils/error_handling.h"
@@ -38,8 +38,6 @@
3838
#define DIR_CMD "ls -d"
3939
#endif
4040

41-
namespace fs = rcpputils::fs;
42-
4341
class AllocatorTest : public ::testing::Test
4442
{
4543
public:
@@ -82,9 +80,9 @@ class LoggingTest : public AllocatorTest
8280
{
8381
}
8482

85-
fs::path find_single_log()
83+
std::filesystem::path find_single_log()
8684
{
87-
fs::path log_dir = get_log_dir();
85+
std::filesystem::path log_dir = get_log_dir();
8886
std::stringstream dir_command;
8987
dir_command << DIR_CMD << " " << (log_dir / get_expected_log_prefix()).string() << "*";
9088

@@ -105,7 +103,7 @@ class LoggingTest : public AllocatorTest
105103
}
106104

107105
std::string line(raw_line);
108-
fs::path line_path(line.substr(0, line.find_last_not_of(" \t\r\n") + 1));
106+
std::filesystem::path line_path(line.substr(0, line.find_last_not_of(" \t\r\n") + 1));
109107
// This should be changed once ros2/rcpputils#68 is resolved
110108
return line_path.is_absolute() ? line_path : log_dir / line_path;
111109
}
@@ -123,9 +121,9 @@ class LoggingTest : public AllocatorTest
123121
return prefix.str();
124122
}
125123

126-
fs::path get_log_dir()
124+
std::filesystem::path get_log_dir()
127125
{
128-
return fs::path(rcutils_get_home_dir()) / ".ros" / "log";
126+
return std::filesystem::path(rcutils_get_home_dir()) / ".ros" / "log";
129127
}
130128
};
131129

rcl_logging_spdlog/test/test_logging_interface.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -13,12 +13,12 @@
1313
// limitations under the License.
1414

1515
#include <limits.h>
16+
#include <filesystem>
1617
#include <fstream>
1718
#include <string>
1819

1920
#include "gmock/gmock.h"
2021

21-
#include "rcpputils/filesystem_helper.hpp"
2222
#include "rcpputils/env.hpp"
2323
#include "rcutils/allocator.h"
2424
#include "rcutils/env.h"
@@ -85,25 +85,25 @@ TEST_F(LoggingTest, init_failure)
8585
rcutils_reset_error();
8686

8787
// Force failure to create directories
88-
rcpputils::fs::path fake_home = rcpputils::fs::current_path() / "fake_home_dir";
89-
ASSERT_TRUE(rcpputils::fs::create_directories(fake_home));
88+
std::filesystem::path fake_home = std::filesystem::current_path() / "fake_home_dir";
89+
ASSERT_TRUE(std::filesystem::create_directories(fake_home));
9090
ASSERT_EQ(true, rcutils_set_env("HOME", fake_home.string().c_str()));
9191

9292
// ...fail to create .ros dir
93-
rcpputils::fs::path ros_dir = fake_home / ".ros";
93+
std::filesystem::path ros_dir = fake_home / ".ros";
9494
std::fstream(ros_dir.string(), std::ios_base::out).close();
9595
EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, allocator));
96-
ASSERT_TRUE(rcpputils::fs::remove(ros_dir));
96+
ASSERT_TRUE(std::filesystem::remove(ros_dir));
9797

9898
// ...fail to create .ros/log dir
99-
ASSERT_TRUE(rcpputils::fs::create_directories(ros_dir));
100-
rcpputils::fs::path ros_log_dir = ros_dir / "log";
99+
ASSERT_TRUE(std::filesystem::create_directories(ros_dir));
100+
std::filesystem::path ros_log_dir = ros_dir / "log";
101101
std::fstream(ros_log_dir.string(), std::ios_base::out).close();
102102
EXPECT_EQ(RCL_LOGGING_RET_ERROR, rcl_logging_external_initialize(nullptr, allocator));
103-
ASSERT_TRUE(rcpputils::fs::remove(ros_log_dir));
104-
ASSERT_TRUE(rcpputils::fs::remove(ros_dir));
103+
ASSERT_TRUE(std::filesystem::remove(ros_log_dir));
104+
ASSERT_TRUE(std::filesystem::remove(ros_dir));
105105

106-
ASSERT_TRUE(rcpputils::fs::remove(fake_home));
106+
ASSERT_TRUE(std::filesystem::remove(fake_home));
107107
}
108108

109109
TEST_F(LoggingTest, init_old_flushing_behavior)

0 commit comments

Comments
 (0)