18 #include <gmock/gmock.h> 19 #include <gtest/gtest.h> 20 #include <boost/ref.hpp> 21 #include <boost/filesystem.hpp> 23 #include <std_msgs/String.h> 26 #include <recorder_msgs/RollingRecorderGoal.h> 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;
44 return expected_status == arg.status.stage;
56 MOCK_METHOD0(setAccepted,
void());
57 MOCK_METHOD0(setRejected,
void());
58 MOCK_METHOD0(setCanceled,
void());
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 &));
72 return *goal_handle_impl;
77 goal_handle_impl->setAccepted();
82 goal_handle_impl->setRejected();
87 goal_handle_impl->setCanceled();
92 return goal_handle_impl->getGoal();
95 void setSucceeded(
const recorder_msgs::RollingRecorderResult & result,
const std::string & msg)
97 goal_handle_impl->setSucceeded(result, msg);
100 void setAborted(
const recorder_msgs::RollingRecorderResult & result,
const std::string & msg)
102 goal_handle_impl->setAborted(result, msg);
105 void setRejected(
const recorder_msgs::RollingRecorderResult & result,
const std::string & msg)
107 goal_handle_impl->setRejected(result, msg);
112 goal_handle_impl->publishFeedback(feedback);
122 MOCK_METHOD1(SetUploadGoal,
void(
const file_uploader_msgs::UploadFilesGoal & goal));
128 MOCK_METHOD1(sendGoal,
void(file_uploader_msgs::UploadFilesGoal));
129 MOCK_METHOD0(waitForResult,
bool());
131 MOCK_CONST_METHOD0(waitForServer,
void());
132 MOCK_CONST_METHOD0(isServerConnected,
bool());
143 std::unique_ptr<RollingRecorderRosbagUploadRequest<MockRollingRecorderGoalHandle, MockS3UploadClient>>
request;
151 action_server_busy(false),
152 goal(new recorder_msgs::RollingRecorderGoal())
154 wordexp_t wordexp_result;
155 wordexp(
"~/.ros/rr_handler_test_dir/", &wordexp_result, 0);
160 path = boost::filesystem::path(rolling_recorder_options.
write_directory);
166 boost::filesystem::remove_all(path);
167 boost::filesystem::create_directories(path);
169 request = std::make_unique<RollingRecorderRosbagUploadRequest<MockRollingRecorderGoalHandle, MockS3UploadClient>>(
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});
182 boost::filesystem::remove_all(path);
183 }
catch (std::exception& e) {
184 AWS_LOGSTREAM_INFO(__func__,
"Caught exception: " << e.what());
190 static int bag_count = 0;
192 std::string bag_name = rolling_recorder_options.
write_directory +
"test_bag_" + std::to_string(bag_count) +
".bag";
194 std_msgs::String str;
195 str.data = std::string(
"foo");
197 bag.
write(
"topic", time, str);
204 EXPECT_CALL(*goal_handle, getGoal()).WillRepeatedly(Return(goal));
209 action_server_busy =
true;
214 action_server_busy =
false;
219 std::vector<std::string> bags;
228 EXPECT_CALL(s3_upload_client, waitForResult(_)).WillRepeatedly(Return(
true));
229 EXPECT_CALL(s3_upload_client, getState()).WillRepeatedly(Return(state));
247 EXPECT_CALL(s3_upload_client, getState()).WillRepeatedly(Return(actionlib::SimpleClientGoalState::StateEnum::ABORTED));
248 EXPECT_CALL(s3_upload_client, waitForResult(_)).WillRepeatedly(Return(
false));
253 EXPECT_CALL(s3_upload_client, sendGoal(_));
257 EXPECT_CALL(s3_upload_client, sendGoal(_)).Times(0);
262 EXPECT_CALL(*goal_handle, setRejected(_, _));
267 EXPECT_CALL(*goal_handle, setAccepted());
272 EXPECT_CALL(*goal_handle, setSucceeded(_, _));
277 EXPECT_CALL(*goal_handle, setCanceled());
282 EXPECT_CALL(*goal_handle, setAborted(_, _));
288 for (
const auto status : statuses) {
289 EXPECT_CALL(*goal_handle, publishFeedback(FeedbackHasStatus(status)));
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())));
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);
318 return ros::Time::now() >= rosbag.getBeginTime();
328 givenActionServerAvailable();
329 givenRollingRecorderGoal();
330 assertGoalIsAccepted();
331 assertPublishFeedback({recorder_msgs::RecorderStatus::PREPARING_UPLOAD});
332 assertUploadGoalIsNotSent();
333 assertGoalIsSuccess();
340 givenActionServerAvailable();
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);
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);
375 givenActionServerBusy();
376 assertGoalIsRejected();
382 int main(
int argc,
char ** argv)
384 ros::init(argc, argv,
"test_rosbag_rolling_recorder");
386 ::testing::InitGoogleTest(&argc, argv);
387 auto result = RUN_ALL_TESTS();
boost::shared_ptr< recorder_msgs::RollingRecorderGoal > getGoal()
RollingRecorderOptions rolling_recorder_options
void assertGoalIsAccepted()
void open(std::string const &filename, uint32_t mode=bagmode::Read)
void givenUploadTimesOut()
std::unique_ptr< RollingRecorderRosbagUploadRequest< MockRollingRecorderGoalHandle, MockS3UploadClient > > request
MATCHER_P(FeedbackHasStatus, expected_status,"")
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
MockRollingRecorderGoalHandle()
void assertGoalIsCanceled()
void assertPublishFeedback(const std::initializer_list< int > &statuses)
void setSucceeded(const recorder_msgs::RollingRecorderResult &result, const std::string &msg)
std::string write_directory
MockRollingRecorderStatus rolling_recorder_status
void publishFeedback(recorder_msgs::RollingRecorderFeedback &feedback)
std::vector< std::string > GetRosbagsToUpload(const std::string &write_directory, const std::function< bool(rosbag::View &)> &select_file)
ros::Duration bag_rollover_time
RollingRecorder rolling_recorder
GoalHandleT & goal_handle
void givenUploadSucceeds()
int main(int argc, char **argv)
RollingRecorderActionServerHandlerTests()
void assertUploadGoalIsNotSent()
MockRollingRecorderGoalHandleImpl(const MockRollingRecorderGoalHandleImpl ©)
TEST_F(RollingRecorderActionServerHandlerTests, TestRollingRecorderActionSucceeds)
void assertUploadGoalIsSent()
std::vector< std::string > givenRecorderIsRunning()
void assertStatusUpdatedCorrectly(const std::vector< std::string > &bags)
~MockRollingRecorderGoalHandleImpl()
void assertGoalIsAborted()
void setAborted(const recorder_msgs::RollingRecorderResult &result, const std::string &msg)
void givenUploadReturns(actionlib::SimpleClientGoalState state)
void givenRollingRecorderGoal()
std::string createRosbagAtTime(ros::Time time)
boost::shared_ptr< recorder_msgs::RollingRecorderGoal > goal
boost::filesystem::path path
void assertGoalIsRejected()
ros::Duration max_record_time
std::shared_ptr< MockRollingRecorderGoalHandleImpl > goal_handle_impl
std::atomic< bool > action_server_busy
void setRejected(const recorder_msgs::RollingRecorderResult &result, const std::string &msg)
static void RollingRecorderRosbagUpload(const RollingRecorderRosbagUploadRequest< GoalHandleT, UploadClientT > &req)
void assertGoalIsSuccess()
void givenActionServerBusy()
MockRollingRecorderGoalHandleImpl & operator*()
void write(std::string const &topic, ros::MessageEvent< T > const &event)
MockS3UploadClient s3_upload_client
void givenActionServerAvailable()
MockRollingRecorderGoalHandle goal_handle