duration_recorder_action_server_handler_test.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2020 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 <gmock/gmock.h>
17 #include <gtest/gtest.h>
18 
23 
24 #include <file_uploader_msgs/UploadFilesAction.h>
25 #include <recorder_msgs/DurationRecorderAction.h>
26 
30 
31 #include <boost/shared_ptr.hpp>
32 #include <boost/ref.hpp>
33 #include <boost/filesystem.hpp>
34 #include <wordexp.h>
35 #include <stdio.h>
36 #include <string>
37 
38 #include <ros/ros.h>
39 
40 using namespace Aws::Rosbag;
41 
42 using ::testing::_;
43 using ::testing::Const;
44 using ::testing::Eq;
45 using ::testing::Field;
46 using ::testing::InSequence;
47 using ::testing::Property;
48 using ::testing::Return;
49 using ::testing::ReturnRef;
50 
51 MATCHER_P(FeedbackHasStatus, expected_status, "") {
52  return expected_status == arg.status.stage;
53 }
54 
55 class MockRosbagRecorder : public Utils::RosbagRecorder<Utils::Recorder>
56 {
57 public:
58  MockRosbagRecorder(): Utils::RosbagRecorder<Utils::Recorder>()
59  {
61  };
63 
64  MOCK_CONST_METHOD0(IsActive, bool());
66  const Utils::RecorderOptions& recorder_options,
67  const std::function<void()>& pre_record,
68  const std::function<void(int)>& post_record
69  ) {
70  options_ = recorder_options;
71  if (return_code_ != Utils::RosbagRecorderRunResult::SKIPPED){
72  pre_record();
73  post_record(rosbag_recorder_exit_code_);
74  }
75  return return_code_;
76  }
77 
79  return options_;
80  }
81 
82  void SetRosbagRecorderExitCode(int exit_code) {
83  rosbag_recorder_exit_code_ = exit_code;
84  }
86  return_code_ = return_code;
87  }
88 private:
92 };
93 
95 {
97  {
98  public:
99  MockServerGoalHandleImpl() = default;
101  {
102  (void) copy;
103  };
105  {
106  };
107 
108  MOCK_METHOD0(setAccepted, void());
109  MOCK_METHOD0(setRejected, void());
110  MOCK_METHOD0(setCanceled, void());
111  MOCK_CONST_METHOD0(getGoal, boost::shared_ptr<recorder_msgs::DurationRecorderGoal>());
112  MOCK_METHOD2(setSucceeded, void(const recorder_msgs::DurationRecorderResult&, const std::string &));
113  MOCK_METHOD2(setAborted, void(const recorder_msgs::DurationRecorderResult&, const std::string &));
114  MOCK_METHOD2(setRejected, void(const recorder_msgs::DurationRecorderResult&, const std::string &));
115  MOCK_CONST_METHOD1(publishFeedback, void(recorder_msgs::DurationRecorderFeedback &));
116  };
117 
118 public:
119  MockServerGoalHandle() : goal_handle_impl(std::make_shared<MockServerGoalHandleImpl>()) {}
120  MockServerGoalHandle(const MockServerGoalHandle & copy) = default;
121 
123  {
124  return *goal_handle_impl;
125  }
126 
127  void setAccepted()
128  {
129  goal_handle_impl->setAccepted();
130  }
131 
132  void setRejected()
133  {
134  goal_handle_impl->setRejected();
135  }
136 
137  void setCanceled()
138  {
139  goal_handle_impl->setCanceled();
140  }
141 
143  {
144  return goal_handle_impl->getGoal();
145  }
146 
147  void setSucceeded(const recorder_msgs::DurationRecorderResult & result, const std::string & msg)
148  {
149  goal_handle_impl->setSucceeded(result, msg);
150  }
151 
152  void setAborted(const recorder_msgs::DurationRecorderResult & result, const std::string & msg)
153  {
154  goal_handle_impl->setAborted(result, msg);
155  }
156 
157  void setRejected(const recorder_msgs::DurationRecorderResult & result, const std::string & msg)
158  {
159  goal_handle_impl->setRejected(result, msg);
160  }
161 
162  void publishFeedback(recorder_msgs::DurationRecorderFeedback & feedback)
163  {
164  goal_handle_impl->publishFeedback(feedback);
165  }
166 
167 private:
168  std::shared_ptr<MockServerGoalHandleImpl> goal_handle_impl;
169 };
170 
171 
173 {
174 public:
175  MOCK_METHOD1(sendGoal, void(file_uploader_msgs::UploadFilesGoal));
176  MOCK_METHOD0(waitForResult, bool());
177  MOCK_METHOD1(waitForResult, bool(ros::Duration));
178  MOCK_CONST_METHOD0(waitForServer, void());
179  MOCK_CONST_METHOD0(isServerConnected, bool());
180  MOCK_CONST_METHOD0(getResult, file_uploader_msgs::UploadFilesResultConstPtr());
181  MOCK_CONST_METHOD0(getState, actionlib::SimpleClientGoalState());
182 };
183 
184 class DurationRecorderActionServerHandlerTests: public ::testing::Test
185 {
186 protected:
189  std::unique_ptr<MockRosbagRecorder> rosbag_recorder;
192  std::vector<std::string> topics_to_record;
194  std::string write_directory;
195  boost::filesystem::path path;
196 public:
197 
199  goal(new recorder_msgs::DurationRecorderGoal()),
200  duration(ros::Duration(5.0)),
201  topics_to_record({"/topic1", "/topic2"})
202  {
203  rosbag_recorder = std::make_unique<MockRosbagRecorder>();
204  // Setup for fake bags
205  wordexp_t wordexp_result;
206  wordexp("~/.ros/dr_handler_test_dir/", &wordexp_result, 0);
207  write_directory = *(wordexp_result.we_wordv);
208  boost::filesystem::create_directories(write_directory);
209  duration_recorder_options.write_directory = write_directory;
210  path = boost::filesystem::path(write_directory);
211  duration_recorder_options.upload_timeout_s = -1;
212  duration_recorder_options.delete_bags_after_upload = false;
213  }
214 
215  void TearDown() override
216  {
217  // Delete all files in the write directory to clean up
218  try {
219  boost::filesystem::remove_all(path);
220  } catch (std::exception& e) {
221  AWS_LOGSTREAM_INFO(__func__, "Caught exception: " << e.what());
222  }
223  }
224 
225  std::string createRosbagAtTime(ros::Time time)
226  {
227  static int bag_count = 0;
228  rosbag::Bag bag;
229  std::string bag_name = write_directory + "test_bag_" + std::to_string(bag_count) + ".bag";
230  bag.open(bag_name, rosbag::bagmode::Write);
231  std_msgs::String str;
232  str.data = std::string("foo");
233  bag_count++;
234  bag.write("topic", time, str);
235  bag.close();
236  return bag_name;
237  }
238 
240  {
241  goal->duration = duration;
242  goal->topics_to_record = topics_to_record;
243  EXPECT_CALL(*server_goal_handle, getGoal()).WillRepeatedly(Return(goal));
244  }
245 
247  {
248  duration = ros::Duration(-1);
249  givenDurationRecorderGoal();
250  }
251 
253  {
254  topics_to_record = {};
255  givenDurationRecorderGoal();
256  }
257 
259  {
260  EXPECT_CALL(*rosbag_recorder, IsActive()).WillRepeatedly(Return(true));
261  }
262 
264  {
265  rosbag_recorder->SetRosbagRecorderReturnCode(Utils::RosbagRecorderRunResult::SKIPPED);
266  }
267 
269  {
270  std::string bag_file_name = createRosbagAtTime(ros::Time::now());
271  rosbag_recorder->SetRosbagRecorderExitCode(0);
272  return bag_file_name;
273  }
274 
276  {
277  rosbag_recorder->SetRosbagRecorderExitCode(1);
278  }
279 
281  {
282  EXPECT_CALL(*rosbag_recorder, IsActive()).WillRepeatedly(Return(false));
283  }
284 
286  {
287  EXPECT_CALL(s3_upload_client, waitForResult()).WillRepeatedly(Return(true));
288  EXPECT_CALL(s3_upload_client, getState()).WillRepeatedly(Return(state));
289  }
290 
292  {
293  givenUploadReturns(actionlib::SimpleClientGoalState(actionlib::SimpleClientGoalState::StateEnum::SUCCEEDED));
294  EXPECT_CALL(s3_upload_client, waitForResult(_)).WillRepeatedly(Return(true));
295  }
296 
298  {
299  givenUploadReturns(actionlib::SimpleClientGoalState(actionlib::SimpleClientGoalState::StateEnum::ABORTED));
300  }
301 
303  {
304  // Choose finite wait so that timeout can occur.
305  // Note that the test won't wait for this time.
306  duration_recorder_options.upload_timeout_s = 1;
307  EXPECT_CALL(s3_upload_client, getState()).WillRepeatedly(Return(actionlib::SimpleClientGoalState::StateEnum::ABORTED));
308  EXPECT_CALL(s3_upload_client, waitForResult(_)).WillRepeatedly(Return(false));
309  }
310 
312  {
313  duration_recorder_options.delete_bags_after_upload = true;
314  file_uploader_msgs::UploadFilesResultConstPtr result_ptr = result;
315 
316  EXPECT_CALL(s3_upload_client, getResult()).WillRepeatedly(Return(result_ptr));
317  }
318 
320  {
321  EXPECT_CALL(s3_upload_client, sendGoal(_));
322  }
323 
325  {
326  EXPECT_CALL(*server_goal_handle, setRejected(_, _));
327  }
328 
330  {
331  EXPECT_CALL(*server_goal_handle, setAccepted());
332  }
333 
335  {
336  EXPECT_CALL(*server_goal_handle, setCanceled());
337  }
338 
340  {
341  EXPECT_CALL(*server_goal_handle, setSucceeded(_, _));
342  }
343 
345  {
346  EXPECT_CALL(*server_goal_handle, setAborted(_, _));
347  }
348 
349  void assertPublishFeedback(const std::initializer_list<int> & statuses)
350  {
351  InSequence s;
352  for (const auto status : statuses) {
353  EXPECT_CALL(*server_goal_handle, publishFeedback(FeedbackHasStatus(status)));
354  }
355  }
356 
358  {
359  auto options = rosbag_recorder->getOptions();
360  ASSERT_EQ(options.max_duration, duration);
361  if (topics_to_record.empty()) {
362  ASSERT_TRUE(rosbag_recorder->getOptions().record_all);
363  }
364  }
365 
366  void assertBagFileCreated(boost::filesystem::path bag_file_path)
367  {
368  ASSERT_TRUE(boost::filesystem::exists(bag_file_path));
369  }
370 
371  void assertBagFileDeleted(boost::filesystem::path bag_file_path)
372  {
373  ASSERT_FALSE(boost::filesystem::exists(bag_file_path));
374  }
375 };
376 
377 TEST_F(DurationRecorderActionServerHandlerTests, TestDurationRecorderStartSucceeds)
378 {
379  givenRecorderNotActive();
380  givenDurationRecorderGoal();
381  givenRecorderRanSuccessfully();
382  givenUploadSucceeds();
383  assertGoalIsAccepted();
384  assertUploadGoalIsSent();
385  assertPublishFeedback({recorder_msgs::RecorderStatus::RECORDING,
386  recorder_msgs::RecorderStatus::PREPARING_UPLOAD,
387  recorder_msgs::RecorderStatus::UPLOADING,
388  recorder_msgs::RecorderStatus::COMPLETE});
389  assertGoalIsSuccess();
391  *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
392 
393  assertRecorderRunWithExpectedOptions();
394 }
395 
396 TEST_F(DurationRecorderActionServerHandlerTests, TestDurationRecorderRecordSucceedsUploadFails)
397 {
398  givenRecorderNotActive();
399  givenDurationRecorderGoal();
400  givenRecorderRanSuccessfully();
401  givenUploadFails();
402  assertGoalIsAccepted();
403  assertUploadGoalIsSent();
404  assertPublishFeedback({recorder_msgs::RecorderStatus::RECORDING,
405  recorder_msgs::RecorderStatus::PREPARING_UPLOAD,
406  recorder_msgs::RecorderStatus::UPLOADING,
407  recorder_msgs::RecorderStatus::COMPLETE});
408  assertGoalIsAborted();
410  *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
411 
412  assertRecorderRunWithExpectedOptions();
413 }
414 
416 {
417  givenRecorderNotActive();
418  givenDurationRecorderGoal();
419  givenRecorderRanUnSuccessfully();
420  assertGoalIsAccepted();
421  assertPublishFeedback({recorder_msgs::RecorderStatus::RECORDING});
422  assertGoalIsAborted();
424  *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
425 
426  assertRecorderRunWithExpectedOptions();
427 }
428 
429 TEST_F(DurationRecorderActionServerHandlerTests, TestDurationRecorderInvalidDurationGoalFails)
430 {
431  givenRecorderNotActive();
432  givenDurationRecorderGoalWithInvalidDuration();
433  assertGoalIsRejected();
435  *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
436 }
437 
438 TEST_F(DurationRecorderActionServerHandlerTests, TestDurationRecorderEmptyTopicsRecordsAll)
439 {
440  givenRecorderNotActive();
441  givenDurationRecorderGoalWithEmptyTopics();
442  givenRecorderRanSuccessfully();
443  givenUploadSucceeds();
444  assertGoalIsAccepted();
445  assertUploadGoalIsSent();
446  assertPublishFeedback({recorder_msgs::RecorderStatus::RECORDING,
447  recorder_msgs::RecorderStatus::PREPARING_UPLOAD,
448  recorder_msgs::RecorderStatus::UPLOADING,
449  recorder_msgs::RecorderStatus::COMPLETE});
450  assertGoalIsSuccess();
452  *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
453 }
454 
455 TEST_F(DurationRecorderActionServerHandlerTests, TestDurationRecorderDeletesFileAfterBagIsUploaded)
456 {
457 
458  boost::shared_ptr<file_uploader_msgs::UploadFilesResult> result(new file_uploader_msgs::UploadFilesResult);
459  givenRecorderNotActive();
460  givenDurationRecorderGoalWithEmptyTopics();
461  std::string bag_file_path = givenRecorderRanSuccessfully();
462  result->files_uploaded = std::vector<std::string>{bag_file_path};
463  givenUploadSucceeds();
464  givenDeleteBagAfterUpload(result);
465  assertGoalIsAccepted();
466  assertUploadGoalIsSent();
467  assertPublishFeedback({recorder_msgs::RecorderStatus::RECORDING,
468  recorder_msgs::RecorderStatus::PREPARING_UPLOAD,
469  recorder_msgs::RecorderStatus::UPLOADING,
470  recorder_msgs::RecorderStatus::COMPLETE,
471  recorder_msgs::RecorderStatus::CLEANUP});
472  assertGoalIsSuccess();
473  assertBagFileCreated(boost::filesystem::path(bag_file_path));
474 
476  *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
477 
478  assertBagFileDeleted(boost::filesystem::path(bag_file_path));
479 }
480 
481 TEST_F(DurationRecorderActionServerHandlerTests, TestDurationRecorderStartAlreadyActive)
482 {
483  givenRecorderActive();
484  assertGoalIsRejected();
485 
487  *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
488 }
489 
490 TEST_F(DurationRecorderActionServerHandlerTests, TestDurationRecorderStartRecorderBecomesActive)
491 {
492  // Test the case where two goals come through in quick succession. Assert that the second goal is rejected.
493  givenRecorderNotActive();
494  givenDurationRecorderGoal();
495  givenRecorderBecomesActive();
496  assertGoalIsRejected();
497 
499  *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
500 }
501 
502 TEST_F(DurationRecorderActionServerHandlerTests, TestDurationRecorderUploadTimedOut)
503 {
504  givenRecorderNotActive();
505  givenDurationRecorderGoal();
506  givenRecorderRanSuccessfully();
507  givenUploadTimesOut();
508  assertGoalIsAccepted();
509  assertUploadGoalIsSent();
510  assertPublishFeedback({recorder_msgs::RecorderStatus::RECORDING,
511  recorder_msgs::RecorderStatus::PREPARING_UPLOAD,
512  recorder_msgs::RecorderStatus::UPLOADING,
513  recorder_msgs::RecorderStatus::COMPLETE});
514  assertGoalIsAborted();
516  *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
517 }
518 
520 {
521  assertGoalIsCanceled();
523  server_goal_handle);
524 }
525 
526 int main(int argc, char ** argv)
527 {
528  ros::Time::init();
529  ::testing::InitGoogleTest(&argc, argv);
530  auto result = RUN_ALL_TESTS();
531  return result;
532 }
void assertPublishFeedback(const std::initializer_list< int > &statuses)
void publishFeedback(recorder_msgs::DurationRecorderFeedback &feedback)
void open(std::string const &filename, uint32_t mode=bagmode::Read)
int main(int argc, char **argv)
XmlRpcServer s
boost::shared_ptr< recorder_msgs::DurationRecorderGoal > goal
void close()
void givenUploadReturns(actionlib::SimpleClientGoalState state)
boost::shared_ptr< recorder_msgs::DurationRecorderGoal > getGoal()
options
void assertBagFileCreated(boost::filesystem::path bag_file_path)
static void init()
static void DurationRecorderStart(Utils::RosbagRecorder< Utils::Recorder > &rosbag_recorder, const DurationRecorderOptions &duration_recorder_options, UploadClientT &upload_client, GoalHandleT &goal_handle)
void assertBagFileDeleted(boost::filesystem::path bag_file_path)
TEST_F(DurationRecorderActionServerHandlerTests, TestDurationRecorderStartSucceeds)
void setAborted(const recorder_msgs::DurationRecorderResult &result, const std::string &msg)
void SetRosbagRecorderReturnCode(Utils::RosbagRecorderRunResult return_code)
void setRejected(const recorder_msgs::DurationRecorderResult &result, const std::string &msg)
Utils::RosbagRecorderRunResult Run(const Utils::RecorderOptions &recorder_options, const std::function< void()> &pre_record, const std::function< void(int)> &post_record)
static Time now()
MATCHER_P(FeedbackHasStatus, expected_status,"")
std::shared_ptr< MockServerGoalHandleImpl > goal_handle_impl
void write(std::string const &topic, ros::MessageEvent< T > const &event)
void givenDeleteBagAfterUpload(boost::shared_ptr< file_uploader_msgs::UploadFilesResult > result)
void setSucceeded(const recorder_msgs::DurationRecorderResult &result, const std::string &msg)


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