rolling_recorder_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 <fstream>
16 #include <iostream>
17 #include <stdlib.h>
18 #include <string>
19 #include <vector>
20 #include <unordered_set>
21 
22 #include <gmock/gmock.h>
23 #include <gtest/gtest.h>
24 
27 #include <aws/core/Aws.h>
28 
29 #include <ros/ros.h>
30 #include <ros/console.h>
31 #include <ros/callback_queue.h>
32 #include <boost/date_time/c_local_time_adjustor.hpp>
33 #include <boost/date_time/posix_time/posix_time.hpp>
34 #include <boost/date_time/posix_time/posix_time_io.hpp>
35 #include <boost/filesystem.hpp>
36 #include <ros/ros.h>
37 #include <ros/console.h>
38 
39 #include <aws/core/utils/logging/AWSLogging.h>
40 #include <aws/core/utils/logging/LogMacros.h>
42 
43 #include <recorder_msgs/RollingRecorderAction.h>
46 #include <recorder_msgs/RollingRecorderAction.h>
47 
48 using namespace Aws::Rosbag;
50 
51 using ::testing::Return;
52 using ::testing::_;
53 using ::testing::ContainerEq;
54 using ::testing::Invoke;
55 
56 class RollingRecorderTest : public ::testing::Test
57 {
58 protected:
59  recorder_msgs::RollingRecorderGoal goal;
66 public:
68  executor(0),
69  nh("~"),
70  action_client(nh, "RosbagRollingRecord")
71  {
72  char dir_template[] = "/tmp/rolling_recorder_testXXXXXX";
73  mkdtemp(dir_template);
74  rolling_recorder_options_.bag_rollover_time = ros::Duration(5);
75  rolling_recorder_options_.max_record_time = ros::Duration(10);
76  rolling_recorder_options_.upload_timeout_s = 3600;
77  rolling_recorder_options_.write_directory = std::string(dir_template) + "/";
78  executor.start();
79  }
80 
81  void TearDown() override
82  {
83  // Delete all files in the write directory to clean up
84  boost::filesystem::path path(rolling_recorder_options_.write_directory);
85  try {
86  boost::filesystem::remove_all(path);
87  } catch (std::exception& e) {
88  AWS_LOGSTREAM_INFO(__func__, "Caught exception: " << e.what());
89  }
90  }
91 
93  {
94  rolling_recorder_.InitializeRollingRecorder(rolling_recorder_options_);
95  }
96 
97  std::string GetFileNameForTimeStamp(const ros::Time& time)
98  {
99  std::stringstream file_name;
100  boost::posix_time::time_facet *const f =
101  new boost::posix_time::time_facet("%Y-%m-%d-%H-%M-%S");
102  boost::posix_time::ptime pt = time.toBoost();
103  boost::posix_time::ptime local_pt = boost::date_time::c_local_adjustor<boost::posix_time::ptime>::utc_to_local(pt);
104  file_name.imbue(std::locale(file_name.getloc(),f));
105  file_name << local_pt;
106  return file_name.str();
107  }
108 
109  std::string CreateRosBagFileStartingAtTime(const ros::Time& time, std::string suffix)
110  {
111  std::string file_name = rolling_recorder_options_.write_directory + GetFileNameForTimeStamp(time) + suffix;
112  std::fstream file;
113  file.open(file_name, std::ios::out);
114  file.close();
115  return file_name;
116  }
117 
118  std::vector<std::string> GivenOldRosBags(int num_bags)
119  {
120  std::vector<std::string> rosbags;
121  for (int i = 0; i < num_bags; ++i) {
122  std::string suffix = "_" + std::to_string(i) + ".bag";
123  rosbags.emplace_back(CreateRosBagFileStartingAtTime(ros::Time::now() - rolling_recorder_options_.max_record_time - ros::Duration(1000), suffix));
124  }
125  return rosbags;
126  }
127 
128  std::vector<std::string> GivenRecentRosBags(int num_bags)
129  {
130  std::vector<std::string> rosbags;
131  for (int i = 0; i < num_bags; ++i) {
132  std::string suffix = "_" + std::to_string(i) + ".bag";
133  rosbags.emplace_back(CreateRosBagFileStartingAtTime(ros::Time::now(), suffix));
134  }
135  return rosbags;
136  }
137 
138  std::vector<std::string> GivenInvalidFileNames(int num_bags)
139  {
140  std::vector<std::string> rosbags;
141  for (int i = 0; i < num_bags; ++i) {
142  std::string suffix = "_" + std::to_string(i) + ".bag";
143  std::string file_name = rolling_recorder_options_.write_directory + "myInvalidBagWithoutADate" + suffix;
144  std::fstream file;
145  file.open(file_name, std::ios::out);
146  file.close();
147  rosbags.emplace_back(file_name);
148  }
149  return rosbags;
150  }
151 
152  bool AllFilesInFilesToDeleteHaveCountComparison(const std::vector<std::string>& bags, boost::function<bool(int)> comparator)
153  {
154  auto files_to_delete = rolling_recorder_.GetRosBagsToDelete();
155  std::unordered_set<std::string> files_set(files_to_delete.begin(), files_to_delete.end());
156  for (const auto& bag: bags) {
157  if (!comparator(files_set.count(bag))) {
158  return false;
159  }
160  }
161  return true;
162  }
163 
164  bool FilesToDeleteContainsAllOf(const std::vector<std::string>& bags)
165  {
166  return AllFilesInFilesToDeleteHaveCountComparison(bags, [](int count) -> bool {return count != 0;});
167  }
168 
169  bool FilesToDeleteContainsNoneOf(const std::vector<std::string>& bags)
170  {
171  return AllFilesInFilesToDeleteHaveCountComparison(bags, [](int count) -> bool {return count == 0;});
172  }
173 };
174 
175 TEST_F(RollingRecorderTest, TestConstructorWithValidParamInput)
176 {
177  ros::Duration max_record_time(5);
178  ros::Duration bag_rollover_time(5);
179 
180  rolling_recorder_options_.max_record_time = max_record_time;
181  rolling_recorder_options_.bag_rollover_time = bag_rollover_time;
182  {
183  Aws::Rosbag::RollingRecorder rolling_recorder;
184  }
185 }
186 
187 TEST_F(RollingRecorderTest, TestInvalidParamInput)
188 {
189  // Case: bag_rollover_time > max_record_time
190  {
191  ros::Duration max_record_time(5);
192  ros::Duration bag_rollover_time(6);
193  rolling_recorder_options_.max_record_time = max_record_time;
194  rolling_recorder_options_.bag_rollover_time = bag_rollover_time;
195 
196  EXPECT_FALSE(rolling_recorder_.ValidInputParam(rolling_recorder_options_));
197  }
198 
199  // Case: bag_rollover_time < 0
200  {
201  ros::Duration max_record_time(-5);
202  ros::Duration bag_rollover_time(6);
203  rolling_recorder_options_.max_record_time = max_record_time;
204  rolling_recorder_options_.bag_rollover_time = bag_rollover_time;
205 
206  EXPECT_FALSE(rolling_recorder_.ValidInputParam(rolling_recorder_options_));
207  }
208 
209  // Case: bag_rollover_time < 0
210  {
211  ros::Duration max_record_time(5);
212  ros::Duration bag_rollover_time(-6);
213  rolling_recorder_options_.max_record_time = max_record_time;
214  rolling_recorder_options_.bag_rollover_time = bag_rollover_time;
215 
216  EXPECT_FALSE(rolling_recorder_.ValidInputParam(rolling_recorder_options_));
217  }
218 }
219 
220 TEST_F(RollingRecorderTest, TestActionReceived)
221 {
222  GivenRollingRecorderInitialized();
223 
224  bool message_received = false;
225  // Wait 10 seconds for server to start
226  ASSERT_TRUE(action_client.waitForActionServerToStart(ros::Duration(10, 0)));
227  auto transition_call_back = [&message_received](RollingRecorderActionClient::GoalHandle goal_handle){
228  if (goal_handle.getCommState().state_ == actionlib::CommState::StateEnum::DONE) {
229  EXPECT_EQ(goal_handle.getTerminalState().state_, actionlib::TerminalState::StateEnum::SUCCEEDED);
230  message_received = true;
231  }
232  };
233  recorder_msgs::RollingRecorderGoal goal;
234  auto gh = action_client.sendGoal(goal, transition_call_back);
235 
236  ros::Duration(1,0).sleep();
237  ASSERT_TRUE(message_received);
238 }
239 
240 TEST_F(RollingRecorderTest, TestGetRosBagsToDeleteDeletesOldBags)
241 {
242  GivenRollingRecorderInitialized();
243  auto old_file_names = GivenOldRosBags(3);
244  auto recent_file_names = GivenRecentRosBags(3);
245  auto invalid_file_names = GivenInvalidFileNames(3);
246  EXPECT_TRUE(FilesToDeleteContainsAllOf(old_file_names));
247  EXPECT_TRUE(FilesToDeleteContainsNoneOf(recent_file_names));
248  EXPECT_TRUE(FilesToDeleteContainsNoneOf(invalid_file_names));
249 }
250 
251 TEST_F(RollingRecorderTest, TestUpdateStatusEffectOnGetRosBagsToDelete)
252 {
253  GivenRollingRecorderInitialized();
254  file_uploader_msgs::UploadFilesGoal upload_goal;
255  upload_goal.files = GivenOldRosBags(3);
256  RollingRecorderStatus status;
257  status.SetUploadGoal(upload_goal);
258  // Update the status to include the files and expect them to be protected from deletion.
259  rolling_recorder_.UpdateStatus(status);
260  EXPECT_TRUE(FilesToDeleteContainsNoneOf(upload_goal.files));
261  // Reset the status and expect the files to now be included in the result.
262  rolling_recorder_.UpdateStatus(RollingRecorderStatus());
263  EXPECT_TRUE(FilesToDeleteContainsAllOf(upload_goal.files));
264 }
265 
266 int main(int argc, char ** argv)
267 {
268  ::testing::InitGoogleTest(&argc, argv);
269  ros::init(argc, argv, "test_rolling_recorder_node");
270  Aws::Utils::Logging::InitializeAWSLogging(
271  Aws::MakeShared<Aws::Utils::Logging::AWSROSLogger>("test_rolling_recorder_node"));
272  auto result = RUN_ALL_TESTS();
273  Aws::Utils::Logging::ShutdownAWSLogging();
274  ros::shutdown();
275  return result;
276 }
bool FilesToDeleteContainsAllOf(const std::vector< std::string > &bags)
bool FilesToDeleteContainsNoneOf(const std::vector< std::string > &bags)
RollingRecorderActionClient action_client
TEST_F(RollingRecorderTest, TestConstructorWithValidParamInput)
std::vector< std::string > GivenOldRosBags(int num_bags)
RollingRecorderActionClient::GoalHandle goal_handle
bool InitializeRollingRecorder(RollingRecorderOptions rolling_recorder_options)
f
void UpdateStatus(const RollingRecorderStatus &status)
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool waitForActionServerToStart(const ros::Duration &timeout=ros::Duration(0, 0))
std::string GetFileNameForTimeStamp(const ros::Time &time)
bool AllFilesInFilesToDeleteHaveCountComparison(const std::vector< std::string > &bags, boost::function< bool(int)> comparator)
RollingRecorder rolling_recorder_
RollingRecorderOptions rolling_recorder_options_
GoalHandle sendGoal(const Goal &goal, TransitionCallback transition_cb=TransitionCallback(), FeedbackCallback feedback_cb=FeedbackCallback())
std::vector< std::string > GetRosBagsToDelete() const
std::vector< std::string > GivenInvalidFileNames(int num_bags)
std::string CreateRosBagFileStartingAtTime(const ros::Time &time, std::string suffix)
int main(int argc, char **argv)
recorder_msgs::RollingRecorderGoal goal
virtual void SetUploadGoal(const file_uploader_msgs::UploadFilesGoal &goal)
CommState getCommState() const
TerminalState getTerminalState() const
std::vector< std::string > GivenRecentRosBags(int num_bags)
static Time now()
bool ValidInputParam(RollingRecorderOptions rolling_recorder_options)
ROSCPP_DECL void shutdown()
boost::posix_time::ptime toBoost() const
ros::AsyncSpinner executor


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