rolling_recorder_action_server_handler_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 
16 #include <fstream>
17 #include <thread>
18 #include <gmock/gmock.h>
19 #include <gtest/gtest.h>
20 #include <boost/ref.hpp>
21 #include <boost/filesystem.hpp>
22 #include <ros/ros.h>
23 #include <std_msgs/String.h>
24 
25 #include <rosbag/bag.h>
26 #include <recorder_msgs/RollingRecorderGoal.h>
30 #include <wordexp.h>
31 
32 using namespace Aws::Rosbag;
33 
34 using ::testing::_;
35 using ::testing::ContainerEq;
36 using ::testing::Field;
37 using ::testing::InSequence;
38 using ::testing::IsEmpty;
39 using ::testing::Return;
40 using ::testing::UnorderedElementsAre;
41 using ::testing::UnorderedElementsAreArray;
42 
43 MATCHER_P(FeedbackHasStatus, expected_status, "") {
44  return expected_status == arg.status.stage;
45 }
46 
48 {
50  {
51  public:
55 
56  MOCK_METHOD0(setAccepted, void());
57  MOCK_METHOD0(setRejected, void());
58  MOCK_METHOD0(setCanceled, void());
59  MOCK_CONST_METHOD0(getGoal, boost::shared_ptr<recorder_msgs::RollingRecorderGoal>());
60  MOCK_METHOD2(setSucceeded, void(const recorder_msgs::RollingRecorderResult&, const std::string &));
61  MOCK_METHOD2(setAborted, void(const recorder_msgs::RollingRecorderResult&, const std::string &));
62  MOCK_METHOD2(setRejected, void(const recorder_msgs::RollingRecorderResult&, const std::string &));
63  MOCK_CONST_METHOD1(publishFeedback, void(recorder_msgs::RollingRecorderFeedback &));
64  };
65 
66 public:
67  MockRollingRecorderGoalHandle() : goal_handle_impl(std::make_shared<MockRollingRecorderGoalHandleImpl>()) {}
69 
71  {
72  return *goal_handle_impl;
73  }
74 
75  void setAccepted()
76  {
77  goal_handle_impl->setAccepted();
78  }
79 
80  void setRejected()
81  {
82  goal_handle_impl->setRejected();
83  }
84 
85  void setCanceled()
86  {
87  goal_handle_impl->setCanceled();
88  }
89 
91  {
92  return goal_handle_impl->getGoal();
93  }
94 
95  void setSucceeded(const recorder_msgs::RollingRecorderResult & result, const std::string & msg)
96  {
97  goal_handle_impl->setSucceeded(result, msg);
98  }
99 
100  void setAborted(const recorder_msgs::RollingRecorderResult & result, const std::string & msg)
101  {
102  goal_handle_impl->setAborted(result, msg);
103  }
104 
105  void setRejected(const recorder_msgs::RollingRecorderResult & result, const std::string & msg)
106  {
107  goal_handle_impl->setRejected(result, msg);
108  }
109 
110  void publishFeedback(recorder_msgs::RollingRecorderFeedback & feedback)
111  {
112  goal_handle_impl->publishFeedback(feedback);
113  }
114 
115 private:
116  std::shared_ptr<MockRollingRecorderGoalHandleImpl> goal_handle_impl;
117 };
118 
120 {
121 public:
122  MOCK_METHOD1(SetUploadGoal, void(const file_uploader_msgs::UploadFilesGoal & goal));
123 };
124 
125 class MockS3UploadClient
126 {
127 public:
128  MOCK_METHOD1(sendGoal, void(file_uploader_msgs::UploadFilesGoal));
129  MOCK_METHOD0(waitForResult, bool());
130  MOCK_METHOD1(waitForResult, bool(ros::Duration));
131  MOCK_CONST_METHOD0(waitForServer, void());
132  MOCK_CONST_METHOD0(isServerConnected, bool());
133  MOCK_CONST_METHOD0(getState, actionlib::SimpleClientGoalState());
134 };
135 
136 class RollingRecorderActionServerHandlerTests: public ::testing::Test
137 {
138 protected:
141  std::atomic<bool> action_server_busy;
143  std::unique_ptr<RollingRecorderRosbagUploadRequest<MockRollingRecorderGoalHandle, MockS3UploadClient>> request;
146  boost::filesystem::path path;
148 
149 public:
151  action_server_busy(false),
152  goal(new recorder_msgs::RollingRecorderGoal())
153  {
154  wordexp_t wordexp_result;
155  wordexp("~/.ros/rr_handler_test_dir/", &wordexp_result, 0);
156  rolling_recorder_options.write_directory = *(wordexp_result.we_wordv);
157  rolling_recorder_options.upload_timeout_s = 3600;
158  rolling_recorder_options.bag_rollover_time = ros::Duration(15);
159  rolling_recorder_options.max_record_time = ros::Duration(100);
160  path = boost::filesystem::path(rolling_recorder_options.write_directory);
161  }
162 
163  void SetUp() override
164  {
165  // Delete all files in the write directory for start testing
166  boost::filesystem::remove_all(path);
167  boost::filesystem::create_directories(path);
168 
169  request = std::make_unique<RollingRecorderRosbagUploadRequest<MockRollingRecorderGoalHandle, MockS3UploadClient>>(
171  .goal_handle = goal_handle,
172  .rolling_recorder_options = rolling_recorder_options,
173  .rosbag_uploader_action_client = s3_upload_client,
174  .action_server_busy = action_server_busy,
175  .recorder_status = &rolling_recorder_status});
176  }
177 
178  void TearDown() override
179  {
180  // Delete all files in the write directory to clean up
181  try {
182  boost::filesystem::remove_all(path);
183  } catch (std::exception& e) {
184  AWS_LOGSTREAM_INFO(__func__, "Caught exception: " << e.what());
185  }
186  }
187 
188  std::string createRosbagAtTime(ros::Time time)
189  {
190  static int bag_count = 0;
191  rosbag::Bag bag;
192  std::string bag_name = rolling_recorder_options.write_directory + "test_bag_" + std::to_string(bag_count) + ".bag";
193  bag.open(bag_name, rosbag::bagmode::Write);
194  std_msgs::String str;
195  str.data = std::string("foo");
196  bag_count++;
197  bag.write("topic", time, str);
198  bag.close();
199  return bag_name;
200  }
201 
203  {
204  EXPECT_CALL(*goal_handle, getGoal()).WillRepeatedly(Return(goal));
205  }
206 
208  {
209  action_server_busy = true;
210  }
211 
213  {
214  action_server_busy = false;
215  }
216 
217  std::vector<std::string> givenRecorderIsRunning()
218  {
219  std::vector<std::string> bags;
220  bags.push_back(createRosbagAtTime(ros::Time::now()-rolling_recorder_options.bag_rollover_time));
221  bags.push_back(createRosbagAtTime(ros::Time::now()-rolling_recorder_options.bag_rollover_time));
222  bags.push_back(createRosbagAtTime(ros::Time::now()-rolling_recorder_options.bag_rollover_time));
223  return bags;
224  }
225 
227  {
228  EXPECT_CALL(s3_upload_client, waitForResult(_)).WillRepeatedly(Return(true));
229  EXPECT_CALL(s3_upload_client, getState()).WillRepeatedly(Return(state));
230  }
231 
233  {
234  givenUploadReturns(actionlib::SimpleClientGoalState(actionlib::SimpleClientGoalState::StateEnum::SUCCEEDED));
235  }
236 
238  {
239  givenUploadReturns(actionlib::SimpleClientGoalState(actionlib::SimpleClientGoalState::StateEnum::ABORTED));
240  }
241 
243  {
244  // Choose finite wait so that timeout can occur.
245  // Note that the test won't wait for this time.
246  rolling_recorder_options.upload_timeout_s = 1;
247  EXPECT_CALL(s3_upload_client, getState()).WillRepeatedly(Return(actionlib::SimpleClientGoalState::StateEnum::ABORTED));
248  EXPECT_CALL(s3_upload_client, waitForResult(_)).WillRepeatedly(Return(false));
249  }
250 
252  {
253  EXPECT_CALL(s3_upload_client, sendGoal(_));
254  }
256  {
257  EXPECT_CALL(s3_upload_client, sendGoal(_)).Times(0);
258  }
259 
261  {
262  EXPECT_CALL(*goal_handle, setRejected(_, _));
263  }
264 
266  {
267  EXPECT_CALL(*goal_handle, setAccepted());
268  }
269 
271  {
272  EXPECT_CALL(*goal_handle, setSucceeded(_, _));
273  }
274 
276  {
277  EXPECT_CALL(*goal_handle, setCanceled());
278  }
279 
281  {
282  EXPECT_CALL(*goal_handle, setAborted(_, _));
283  }
284 
285  void assertPublishFeedback(const std::initializer_list<int> & statuses)
286  {
287  InSequence s;
288  for (const auto status : statuses) {
289  EXPECT_CALL(*goal_handle, publishFeedback(FeedbackHasStatus(status)));
290  }
291  }
292 
293  void assertStatusUpdatedCorrectly(const std::vector<std::string> & bags)
294  {
295  InSequence s;
296  EXPECT_CALL(rolling_recorder_status, SetUploadGoal(Field(&file_uploader_msgs::UploadFilesGoal::files, UnorderedElementsAreArray(bags))));
297  EXPECT_CALL(rolling_recorder_status, SetUploadGoal(Field(&file_uploader_msgs::UploadFilesGoal::files, IsEmpty())));
298  }
299 };
300 
301 TEST_F(RollingRecorderActionServerHandlerTests, TestRollingRecorderActionSucceeds)
302 {
303  givenActionServerAvailable();
304  givenUploadSucceeds();
305  auto bags = givenRecorderIsRunning();
306  givenRollingRecorderGoal();
307  assertGoalIsAccepted();
308  assertPublishFeedback({recorder_msgs::RecorderStatus::PREPARING_UPLOAD,
309  recorder_msgs::RecorderStatus::UPLOADING,
310  recorder_msgs::RecorderStatus::COMPLETE});
311  assertUploadGoalIsSent();
312  assertGoalIsSuccess();
313  assertStatusUpdatedCorrectly(bags);
314 
315  ASSERT_FALSE(Utils::GetRosbagsToUpload(rolling_recorder_options.write_directory,
316  [](rosbag::View& rosbag) -> bool
317  {
318  return ros::Time::now() >= rosbag.getBeginTime();
319  }
320  ).empty());
321 
323  *request);
324 }
325 
326 TEST_F(RollingRecorderActionServerHandlerTests, TestRollingRecorderSucceedsDoesntUploadWithNoFiles)
327 {
328  givenActionServerAvailable();
329  givenRollingRecorderGoal();
330  assertGoalIsAccepted();
331  assertPublishFeedback({recorder_msgs::RecorderStatus::PREPARING_UPLOAD});
332  assertUploadGoalIsNotSent();
333  assertGoalIsSuccess();
335  *request);
336 }
337 
338 TEST_F(RollingRecorderActionServerHandlerTests, TestRollingRecorderUploadFails)
339 {
340  givenActionServerAvailable();
341  givenUploadFails();
342  auto bags = givenRecorderIsRunning();
343  givenRollingRecorderGoal();
344  assertGoalIsAccepted();
345  assertPublishFeedback({recorder_msgs::RecorderStatus::PREPARING_UPLOAD,
346  recorder_msgs::RecorderStatus::UPLOADING,
347  recorder_msgs::RecorderStatus::COMPLETE});
348  assertUploadGoalIsSent();
349  assertGoalIsAborted();
350  assertStatusUpdatedCorrectly(bags);
352  *request);
353 }
354 
355 TEST_F(RollingRecorderActionServerHandlerTests, TestRollingRecorderUploadTimesOut)
356 {
357  givenActionServerAvailable();
358  givenUploadTimesOut();
359  auto bags = givenRecorderIsRunning();
360  givenRollingRecorderGoal();
361  assertGoalIsAccepted();
362  assertPublishFeedback({recorder_msgs::RecorderStatus::PREPARING_UPLOAD,
363  recorder_msgs::RecorderStatus::UPLOADING,
364  recorder_msgs::RecorderStatus::COMPLETE});
365  assertUploadGoalIsSent();
366  assertGoalIsAborted();
367  assertStatusUpdatedCorrectly(bags);
369  *request);
370 }
371 
372 TEST_F(RollingRecorderActionServerHandlerTests, TestRollingRecorderActionServerBusy)
373 {
374  // Test when action server is processing a goal
375  givenActionServerBusy();
376  assertGoalIsRejected();
377 
379  *request);
380 }
381 
382 int main(int argc, char ** argv)
383 {
384  ros::init(argc, argv, "test_rosbag_rolling_recorder");
385  ros::Time::init();
386  ::testing::InitGoogleTest(&argc, argv);
387  auto result = RUN_ALL_TESTS();
388  return result;
389 }
boost::shared_ptr< recorder_msgs::RollingRecorderGoal > getGoal()
void open(std::string const &filename, uint32_t mode=bagmode::Read)
std::unique_ptr< RollingRecorderRosbagUploadRequest< MockRollingRecorderGoalHandle, MockS3UploadClient > > request
XmlRpcServer s
MATCHER_P(FeedbackHasStatus, expected_status,"")
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void assertPublishFeedback(const std::initializer_list< int > &statuses)
void setSucceeded(const recorder_msgs::RollingRecorderResult &result, const std::string &msg)
void close()
void publishFeedback(recorder_msgs::RollingRecorderFeedback &feedback)
std::vector< std::string > GetRosbagsToUpload(const std::string &write_directory, const std::function< bool(rosbag::View &)> &select_file)
Definition: file_utils.cpp:181
int main(int argc, char **argv)
static void init()
TEST_F(RollingRecorderActionServerHandlerTests, TestRollingRecorderActionSucceeds)
void assertStatusUpdatedCorrectly(const std::vector< std::string > &bags)
void setAborted(const recorder_msgs::RollingRecorderResult &result, const std::string &msg)
void givenUploadReturns(actionlib::SimpleClientGoalState state)
boost::shared_ptr< recorder_msgs::RollingRecorderGoal > goal
static Time now()
std::shared_ptr< MockRollingRecorderGoalHandleImpl > goal_handle_impl
void setRejected(const recorder_msgs::RollingRecorderResult &result, const std::string &msg)
static void RollingRecorderRosbagUpload(const RollingRecorderRosbagUploadRequest< GoalHandleT, UploadClientT > &req)
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