file_utils_test.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License").
5  * You may not use this file except in compliance with the License.
6  * A copy of the License is located at
7  *
8  * http://aws.amazon.com/apache2.0
9  *
10  * or in the "license" file accompanying this file. This file is distributed
11  * on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either
12  * express or implied. See the License for the specific language governing
13  * permissions and limitations under the License.
14  */
15 #include <chrono>
16 #include <fstream>
17 #include <string>
18 #include <vector>
19 #include <stdlib.h>
20 #include <sys/stat.h>
21 #include <thread>
22 
23 #include <cstring>
24 #include <cerrno>
25 #include <string>
26 #include <unistd.h>
27 #include <wordexp.h>
28 
29 #include <boost/filesystem.hpp>
30 #include <ros/ros.h>
31 #include <std_msgs/String.h>
32 
33 #include <gmock/gmock.h>
34 #include <gtest/gtest.h>
35 
38 
39 
40 using namespace Aws::Rosbag::Utils;
41 using ::testing::_;
42 using ::testing::UnorderedElementsAre;
43 
44 class ExpandAndCreateDirTests: public ::testing::Test
45 {
46 public:
48  {
49  // Delete any existing test directory for start testing
50  boost::filesystem::remove_all(test_dir);
51 
52  old_home = getenv("HOME");
53  }
54 
56  {
57  // Delete any existing test directory for cleaning up
58  boost::filesystem::remove_all(test_dir);
59 
60  if (old_home == nullptr) {
61  unsetenv("HOME");
62  } else {
63  setenv("HOME", old_home, true);
64  }
65  }
66 
67 protected:
68  static constexpr char test_dir[] = "./temp_file_utils_test_dir";
69  static constexpr char test_dir_str[] = "~/temp_file_utils_test_dir";
70 
71 private:
72  const char * old_home;
73 };
74 
75 constexpr char ExpandAndCreateDirTests::test_dir[];
77 
78 class GetRosbagToUploadTests: public ::testing::Test
79 {
80 public:
82  {
83  wordexp_t wordexp_result;
84  wordexp("~/.ros/file_utils_test_dir/", &wordexp_result, 0);
85  write_directory = *(wordexp_result.we_wordv);
86  path = boost::filesystem::path(write_directory);
87  }
88 
89  void SetUp() override
90  {
92  // Delete all files in the write directory for start testing
93  boost::filesystem::remove_all(path);
94  boost::filesystem::create_directories(path);
95  }
96 
97  void TearDown() override
98  {
99  // Delete all files in the write directory for cleaning up
100  boost::filesystem::remove_all(path);
101  }
102 
103  void createRosbagInWriteDirectory(std::vector<std::string> bag_filenames) {
104  for (std::string bag_filename : bag_filenames) {
105  rosbag::Bag bag_file;
106  bag_file.open(write_directory + bag_filename, rosbag::bagmode::Write);
107  std_msgs::String str_msg;
108  str_msg.data = std::string("foo");
109  bag_file.write("/topic", ros::Time::now(), str_msg);
110  bag_file.close();
111  }
112  }
113 
114  std::vector<std::string> checkGetRosbagsToUploadFileExtensions(ros::Time time_of_goal_received) {
115  std::vector<std::string> bag_files_in_write_directory = Aws::Rosbag::Utils::GetRosbagsToUpload(write_directory,
116  [time_of_goal_received](rosbag::View& rosbag) -> bool {return time_of_goal_received >= rosbag.getBeginTime();}
117  );
118  for (std::string bag_file_in_write_directory : bag_files_in_write_directory) {
119  EXPECT_EQ(boost::filesystem::extension(bag_file_in_write_directory), ".bag");
120  }
121  return bag_files_in_write_directory;
122  }
123 
124 protected:
125  std::string write_directory;
126  boost::filesystem::path path;
127 };
128 
129 TEST_F(ExpandAndCreateDirTests, TestForNonexistingDirectory)
130 {
131  std::string expanded_dir;
132  setenv("HOME", ".", true);
133  bool success = ExpandAndCreateDir(test_dir_str, expanded_dir);
134  ASSERT_EQ(test_dir, expanded_dir);
135  ASSERT_TRUE(success);
136  ASSERT_TRUE(boost::filesystem::exists(expanded_dir));
137 }
138 
139 TEST_F(ExpandAndCreateDirTests, TestForExistingDirectory)
140 {
141  // place an existing directory where it should be
142  boost::filesystem::create_directories(test_dir);
143 
144  // test
145  std::string expanded_dir;
146  setenv("HOME", ".", true);
147  bool success = ExpandAndCreateDir(test_dir_str, expanded_dir);
148  ASSERT_EQ(test_dir, expanded_dir);
149  ASSERT_TRUE(success);
150  ASSERT_TRUE(boost::filesystem::exists(expanded_dir));
151 }
152 
153 TEST_F(ExpandAndCreateDirTests, DISABLED_TestForNonwriteableDirectory)
154 {
155  using namespace boost::filesystem;
156 
157  // place an existing directory where it should be
158  create_directories(test_dir);
159  permissions(test_dir, owner_read | group_read | others_read);
160 
161  // test
162  std::string expanded_dir;
163  setenv("HOME", ".", true);
164  bool success = ExpandAndCreateDir(test_dir_str, expanded_dir);
165  ASSERT_EQ(test_dir, expanded_dir);
166  ASSERT_FALSE(success); // this test will fail if run as root
167 }
168 
169 TEST_F(ExpandAndCreateDirTests, TestForImpossibleDirectory)
170 {
171  // create a file where the directory should be
172  std::ofstream temp_file(test_dir);
173  temp_file.close();
174 
175  // test
176  std::string expanded_dir;
177  setenv("HOME", ".", true);
178  bool success = ExpandAndCreateDir(test_dir_str, expanded_dir);
179  ASSERT_EQ(test_dir, expanded_dir);
180  ASSERT_FALSE(success);
181 }
182 
183 TEST(DeleteFileTest, TestFileRemovalSucceeds)
184 {
185  std::string path = "./TestRosbagRemovalSuccessfulCase.bag";
186  std::ofstream file(path);
187  file.close();
189 }
190 
191 TEST(DeleteFileTest, TestFileRemovalFailsFileDoesntExist)
192 {
193  EXPECT_EQ(DeleteFile("/I/Am/Nowhere/To/Be/Found.bag"), Aws::Rosbag::RecorderErrorCode::FILE_NOT_FOUND);
194 }
195 
196 TEST(DeleteFileTest, TestRemoveDirectoryFails)
197 {
198  char dir_template[] = "/tmp/DeleteFileTestXXXXXX";
199  mkdtemp(dir_template);
201  rmdir(dir_template);
202 }
203 
204 TEST(GetRosBagStartTimeTest, SucceedsOnProperlyFormattedInputs)
205 {
206  // Test all possible combinations of properly formatted time stamp with/without directory,
207  // bag number, file extension
208  EXPECT_EQ(ros::Time(1579021994), GetRosBagStartTime("2020-01-14-17-13-14"));
209  EXPECT_EQ(ros::Time(1579021994), GetRosBagStartTime("2020-01-14-17-13-14_1"));
210  EXPECT_EQ(ros::Time(1579021994), GetRosBagStartTime("2020-01-14-17-13-14_1.bag"));
211  EXPECT_EQ(ros::Time(1579021994), GetRosBagStartTime("dir/dir/2020-01-14-17-13-14_1.bag"));
212  EXPECT_EQ(ros::Time(1579021994), GetRosBagStartTime("2020-01-14-17-13-14.bag"));
213  EXPECT_EQ(ros::Time(1579021994), GetRosBagStartTime("dir/dir/2020-01-14-17-13-14.bag"));
214  EXPECT_EQ(ros::Time(1579021994), GetRosBagStartTime("dir/dir/2020-01-14-17-13-14_1"));
215  EXPECT_EQ(ros::Time(1579021994), GetRosBagStartTime("dir/2020-01-14-17-13-14"));
216  EXPECT_EQ(ros::Time(1579021994), GetRosBagStartTime("dir/_2020-01-14-17-13-14_2.bag"));
217 }
218 
219 TEST(GetRosBagStartTimeTest, ReturnsZeroOnInvalidInput)
220 {
221  // Input is invalid date is not proper format
222  EXPECT_TRUE(GetRosBagStartTime("dir/dir/2020-01-14-17-13-14/1.bag").isZero());
223  // Input is invalid because the date is correctly formatted but is too far in the future
224  EXPECT_TRUE(GetRosBagStartTime("3020-01-14-17-13-14_1.bag").isZero());
225 }
226 
227 TEST_F(GetRosbagToUploadTests, TestGetRosbagToUploadMixedFiles)
228 {
229  createRosbagInWriteDirectory(std::vector<std::string>({"test1.bag", "nonbagfile", "test2.bag"}));
230 
231  auto goal_received_time = ros::Time::now();
232  // We want to make absolutely sure that bags created after setting goal_received_time will have a later start time. Short sleep will do.
233  std::this_thread::sleep_for(std::chrono::duration<double, std::milli>(10));
234 
235  createRosbagInWriteDirectory(std::vector<std::string>({"test_late1.bag", "nonbagfile2", "test_late2.bag"}));
236 
237  EXPECT_THAT(checkGetRosbagsToUploadFileExtensions(goal_received_time),
238  UnorderedElementsAre(write_directory + "test1.bag", write_directory + "test2.bag"));
239 }
240 
241 TEST_F(GetRosbagToUploadTests, TestGetRosbagToUploadNoEligibleFiles)
242 {
243  ros::Time time_of_function_called(ros::Time::now());
244  std::vector<std::string> bag_files_to_create{"test1.bag.test", "test1.bag.random", "test1.bag.how.about.this.Bag", "text_file.txt"};
245  createRosbagInWriteDirectory(std::move(bag_files_to_create));
246  EXPECT_EQ(checkGetRosbagsToUploadFileExtensions(time_of_function_called),
247  std::vector<std::string>({}));
248 }
boost::filesystem::path path
static constexpr char test_dir_str[]
void open(std::string const &filename, uint32_t mode=bagmode::Read)
TEST(DeleteFileTest, TestFileRemovalSucceeds)
bool ExpandAndCreateDir(const std::string &dir, std::string &expanded_dir)
Definition: file_utils.cpp:57
TEST_F(ExpandAndCreateDirTests, TestForNonexistingDirectory)
std::vector< std::string > checkGetRosbagsToUploadFileExtensions(ros::Time time_of_goal_received)
ros::Time GetRosBagStartTime(const std::string &file_path)
Get the time a rosbag started.
Definition: file_utils.cpp:119
void close()
std::vector< std::string > GetRosbagsToUpload(const std::string &write_directory, const std::function< bool(rosbag::View &)> &select_file)
Definition: file_utils.cpp:181
static constexpr char test_dir[]
Aws::Rosbag::RecorderErrorCode DeleteFile(const std::string &file_path)
delete a file
Definition: file_utils.cpp:93
ros::Time getBeginTime()
static void init()
void createRosbagInWriteDirectory(std::vector< std::string > bag_filenames)
static Time now()
void TearDown() override
void write(std::string const &topic, ros::MessageEvent< T > const &event)


rosbag_cloud_recorders
Author(s): AWS RoboMaker
autogenerated on Tue Jun 1 2021 02:51:27