|
12 | 12 | // See the License for the specific language governing permissions and |
13 | 13 | // limitations under the License. |
14 | 14 |
|
| 15 | +#include <filesystem> |
15 | 16 | #include <iostream> |
16 | 17 | #include <string> |
17 | 18 |
|
18 | 19 | #include "gtest/gtest.h" |
19 | 20 |
|
20 | | -#include "rcpputils/filesystem_helper.hpp" |
21 | 21 | #include "rcpputils/env.hpp" |
22 | 22 | #include "rcutils/allocator.h" |
23 | 23 | #include "rcutils/env.h" |
@@ -79,104 +79,104 @@ TEST(test_logging_directory, directory) |
79 | 79 | directory = nullptr; |
80 | 80 |
|
81 | 81 | // 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"); |
83 | 83 | ASSERT_EQ(true, rcutils_set_env("HOME", fake_home.string().c_str())); |
84 | 84 | 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"; |
86 | 86 | 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()); |
88 | 88 | allocator.deallocate(directory, allocator.state); |
89 | 89 | directory = nullptr; |
90 | 90 |
|
91 | 91 | // Use $ROS_LOG_DIR if it is set |
92 | 92 | 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); |
94 | 94 | ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", my_log_dir.string().c_str())); |
95 | 95 | 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()); |
97 | 97 | allocator.deallocate(directory, allocator.state); |
98 | 98 | directory = nullptr; |
99 | 99 | // Make sure it converts path separators when necessary |
100 | 100 | ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", my_log_dir_raw)); |
101 | 101 | 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()); |
103 | 103 | allocator.deallocate(directory, allocator.state); |
104 | 104 | directory = nullptr; |
105 | 105 | // Setting ROS_HOME won't change anything since ROS_LOG_DIR is used first |
106 | 106 | ASSERT_EQ(true, rcutils_set_env("ROS_HOME", "/this/wont/be/used")); |
107 | 107 | 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()); |
109 | 109 | allocator.deallocate(directory, allocator.state); |
110 | 110 | directory = nullptr; |
111 | 111 | ASSERT_EQ(true, rcutils_set_env("ROS_HOME", nullptr)); |
112 | 112 | // Empty is considered unset |
113 | 113 | ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", "")); |
114 | 114 | 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()); |
116 | 116 | allocator.deallocate(directory, allocator.state); |
117 | 117 | directory = nullptr; |
118 | 118 | // Make sure '~' is expanded to the home directory |
119 | 119 | ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", "~/logdir")); |
120 | 120 | 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()); |
123 | 123 | allocator.deallocate(directory, allocator.state); |
124 | 124 | directory = nullptr; |
125 | 125 | // 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"); |
127 | 127 | ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", prefixed_fake_log_dir.string().c_str())); |
128 | 128 | 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()); |
130 | 130 | allocator.deallocate(directory, allocator.state); |
131 | 131 | directory = nullptr; |
132 | 132 | ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", "~")); |
133 | 133 | 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()); |
135 | 135 | allocator.deallocate(directory, allocator.state); |
136 | 136 | directory = nullptr; |
137 | | - rcpputils::fs::path home_trailing_slash(fake_home.string() + "/"); |
| 137 | + std::filesystem::path home_trailing_slash(fake_home.string() + "/"); |
138 | 138 | ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", "~/")); |
139 | 139 | 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()); |
141 | 141 | allocator.deallocate(directory, allocator.state); |
142 | 142 | directory = nullptr; |
143 | 143 |
|
144 | 144 | ASSERT_EQ(true, rcutils_set_env("ROS_LOG_DIR", nullptr)); |
145 | 145 |
|
146 | 146 | // 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"; |
148 | 148 | ASSERT_EQ(true, rcutils_set_env("ROS_HOME", fake_ros_home.string().c_str())); |
149 | 149 | 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()); |
152 | 152 | allocator.deallocate(directory, allocator.state); |
153 | 153 | directory = nullptr; |
154 | 154 | // Make sure it converts path separators when necessary |
155 | 155 | const char * my_ros_home_raw = "/my/ros/home"; |
156 | 156 | ASSERT_EQ(true, rcutils_set_env("ROS_HOME", my_ros_home_raw)); |
157 | 157 | 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()); |
160 | 160 | allocator.deallocate(directory, allocator.state); |
161 | 161 | directory = nullptr; |
162 | 162 | // Empty is considered unset |
163 | 163 | ASSERT_EQ(true, rcutils_set_env("ROS_HOME", "")); |
164 | 164 | 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()); |
166 | 166 | allocator.deallocate(directory, allocator.state); |
167 | 167 | directory = nullptr; |
168 | 168 | // Make sure '~' is expanded to the home directory |
169 | 169 | ASSERT_EQ(true, rcutils_set_env("ROS_HOME", "~/.fakeroshome")); |
170 | 170 | 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()); |
172 | 172 | allocator.deallocate(directory, allocator.state); |
173 | 173 | directory = nullptr; |
174 | 174 | // 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"; |
177 | 177 | ASSERT_EQ(true, rcutils_set_env("ROS_HOME", prefixed_fake_ros_home.string().c_str())); |
178 | 178 | 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()); |
180 | 180 | allocator.deallocate(directory, allocator.state); |
181 | 181 | directory = nullptr; |
182 | 182 |
|
|
0 commit comments