16 #include <gmock/gmock.h> 17 #include <gtest/gtest.h> 24 #include <file_uploader_msgs/UploadFilesAction.h> 25 #include <recorder_msgs/DurationRecorderAction.h> 31 #include <boost/shared_ptr.hpp> 32 #include <boost/ref.hpp> 33 #include <boost/filesystem.hpp> 43 using ::testing::Const;
45 using ::testing::Field;
46 using ::testing::InSequence;
47 using ::testing::Property;
48 using ::testing::Return;
49 using ::testing::ReturnRef;
52 return expected_status == arg.status.stage;
64 MOCK_CONST_METHOD0(IsActive,
bool());
67 const std::function<
void()>& pre_record,
68 const std::function<
void(
int)>& post_record
70 options_ = recorder_options;
73 post_record(rosbag_recorder_exit_code_);
83 rosbag_recorder_exit_code_ = exit_code;
86 return_code_ = return_code;
108 MOCK_METHOD0(setAccepted,
void());
109 MOCK_METHOD0(setRejected,
void());
110 MOCK_METHOD0(setCanceled,
void());
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 &));
124 return *goal_handle_impl;
129 goal_handle_impl->setAccepted();
134 goal_handle_impl->setRejected();
139 goal_handle_impl->setCanceled();
144 return goal_handle_impl->getGoal();
147 void setSucceeded(
const recorder_msgs::DurationRecorderResult & result,
const std::string & msg)
149 goal_handle_impl->setSucceeded(result, msg);
152 void setAborted(
const recorder_msgs::DurationRecorderResult & result,
const std::string & msg)
154 goal_handle_impl->setAborted(result, msg);
157 void setRejected(
const recorder_msgs::DurationRecorderResult & result,
const std::string & msg)
159 goal_handle_impl->setRejected(result, msg);
164 goal_handle_impl->publishFeedback(feedback);
175 MOCK_METHOD1(sendGoal,
void(file_uploader_msgs::UploadFilesGoal));
176 MOCK_METHOD0(waitForResult,
bool());
178 MOCK_CONST_METHOD0(waitForServer,
void());
179 MOCK_CONST_METHOD0(isServerConnected,
bool());
180 MOCK_CONST_METHOD0(getResult, file_uploader_msgs::UploadFilesResultConstPtr());
199 goal(new recorder_msgs::DurationRecorderGoal()),
200 duration(
ros::Duration(5.0)),
201 topics_to_record({
"/topic1",
"/topic2"})
203 rosbag_recorder = std::make_unique<MockRosbagRecorder>();
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);
210 path = boost::filesystem::path(write_directory);
219 boost::filesystem::remove_all(path);
220 }
catch (std::exception& e) {
221 AWS_LOGSTREAM_INFO(__func__,
"Caught exception: " << e.what());
227 static int bag_count = 0;
229 std::string bag_name = write_directory +
"test_bag_" + std::to_string(bag_count) +
".bag";
231 std_msgs::String str;
232 str.data = std::string(
"foo");
234 bag.
write(
"topic", time, str);
241 goal->duration = duration;
242 goal->topics_to_record = topics_to_record;
243 EXPECT_CALL(*server_goal_handle, getGoal()).WillRepeatedly(Return(goal));
249 givenDurationRecorderGoal();
254 topics_to_record = {};
255 givenDurationRecorderGoal();
260 EXPECT_CALL(*rosbag_recorder, IsActive()).WillRepeatedly(Return(
true));
271 rosbag_recorder->SetRosbagRecorderExitCode(0);
272 return bag_file_name;
277 rosbag_recorder->SetRosbagRecorderExitCode(1);
282 EXPECT_CALL(*rosbag_recorder, IsActive()).WillRepeatedly(Return(
false));
287 EXPECT_CALL(s3_upload_client, waitForResult()).WillRepeatedly(Return(
true));
288 EXPECT_CALL(s3_upload_client, getState()).WillRepeatedly(Return(state));
294 EXPECT_CALL(s3_upload_client, waitForResult(_)).WillRepeatedly(Return(
true));
307 EXPECT_CALL(s3_upload_client, getState()).WillRepeatedly(Return(actionlib::SimpleClientGoalState::StateEnum::ABORTED));
308 EXPECT_CALL(s3_upload_client, waitForResult(_)).WillRepeatedly(Return(
false));
314 file_uploader_msgs::UploadFilesResultConstPtr result_ptr = result;
316 EXPECT_CALL(s3_upload_client, getResult()).WillRepeatedly(Return(result_ptr));
321 EXPECT_CALL(s3_upload_client, sendGoal(_));
326 EXPECT_CALL(*server_goal_handle, setRejected(_, _));
331 EXPECT_CALL(*server_goal_handle, setAccepted());
336 EXPECT_CALL(*server_goal_handle, setCanceled());
341 EXPECT_CALL(*server_goal_handle, setSucceeded(_, _));
346 EXPECT_CALL(*server_goal_handle, setAborted(_, _));
352 for (
const auto status : statuses) {
353 EXPECT_CALL(*server_goal_handle, publishFeedback(FeedbackHasStatus(status)));
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);
368 ASSERT_TRUE(boost::filesystem::exists(bag_file_path));
373 ASSERT_FALSE(boost::filesystem::exists(bag_file_path));
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);
393 assertRecorderRunWithExpectedOptions();
398 givenRecorderNotActive();
399 givenDurationRecorderGoal();
400 givenRecorderRanSuccessfully();
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);
412 assertRecorderRunWithExpectedOptions();
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);
426 assertRecorderRunWithExpectedOptions();
431 givenRecorderNotActive();
432 givenDurationRecorderGoalWithInvalidDuration();
433 assertGoalIsRejected();
435 *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
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);
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));
476 *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
478 assertBagFileDeleted(boost::filesystem::path(bag_file_path));
483 givenRecorderActive();
484 assertGoalIsRejected();
487 *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
493 givenRecorderNotActive();
494 givenDurationRecorderGoal();
495 givenRecorderBecomesActive();
496 assertGoalIsRejected();
499 *rosbag_recorder, duration_recorder_options, s3_upload_client, server_goal_handle);
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);
521 assertGoalIsCanceled();
526 int main(
int argc,
char ** argv)
529 ::testing::InitGoogleTest(&argc, argv);
530 auto result = RUN_ALL_TESTS();
void assertUploadGoalIsSent()
void assertRecorderRunWithExpectedOptions()
void assertPublishFeedback(const std::initializer_list< int > &statuses)
void publishFeedback(recorder_msgs::DurationRecorderFeedback &feedback)
std::string createRosbagAtTime(ros::Time time)
void assertGoalIsAborted()
void open(std::string const &filename, uint32_t mode=bagmode::Read)
void assertGoalIsSuccess()
int main(int argc, char **argv)
boost::filesystem::path path
Aws::Rosbag::DurationRecorderOptions duration_recorder_options
MockS3UploadClient s3_upload_client
void givenRecorderNotActive()
DurationRecorderActionServerHandlerTests()
void givenUploadTimesOut()
~MockServerGoalHandleImpl()
boost::shared_ptr< recorder_msgs::DurationRecorderGoal > goal
Utils::RecorderOptions options_
Utils::RecorderOptions getOptions()
std::unique_ptr< MockRosbagRecorder > rosbag_recorder
void givenUploadReturns(actionlib::SimpleClientGoalState state)
boost::shared_ptr< recorder_msgs::DurationRecorderGoal > getGoal()
MockServerGoalHandleImpl & operator*()
std::string write_directory
void SetRosbagRecorderExitCode(int exit_code)
void assertGoalIsAccepted()
void givenRecorderBecomesActive()
void assertGoalIsRejected()
void assertBagFileCreated(boost::filesystem::path bag_file_path)
void givenDurationRecorderGoalWithEmptyTopics()
static void DurationRecorderStart(Utils::RosbagRecorder< Utils::Recorder > &rosbag_recorder, const DurationRecorderOptions &duration_recorder_options, UploadClientT &upload_client, GoalHandleT &goal_handle)
std::string write_directory
void givenDurationRecorderGoal()
void assertBagFileDeleted(boost::filesystem::path bag_file_path)
void givenDurationRecorderGoalWithInvalidDuration()
std::vector< std::string > topics_to_record
static void CancelDurationRecorder(GoalHandleT &goal_handle)
TEST_F(DurationRecorderActionServerHandlerTests, TestDurationRecorderStartSucceeds)
Utils::RosbagRecorderRunResult return_code_
int rosbag_recorder_exit_code_
void givenRecorderActive()
void givenRecorderRanUnSuccessfully()
void givenUploadSucceeds()
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)
bool delete_bags_after_upload
MATCHER_P(FeedbackHasStatus, expected_status,"")
MockServerGoalHandle server_goal_handle
std::string givenRecorderRanSuccessfully()
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)
MockServerGoalHandleImpl(const MockServerGoalHandleImpl ©)
void assertGoalIsCanceled()
void setSucceeded(const recorder_msgs::DurationRecorderResult &result, const std::string &msg)