20 #include <unordered_set> 22 #include <gmock/gmock.h> 23 #include <gtest/gtest.h> 27 #include <aws/core/Aws.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> 39 #include <aws/core/utils/logging/AWSLogging.h> 40 #include <aws/core/utils/logging/LogMacros.h> 43 #include <recorder_msgs/RollingRecorderAction.h> 46 #include <recorder_msgs/RollingRecorderAction.h> 51 using ::testing::Return;
53 using ::testing::ContainerEq;
54 using ::testing::Invoke;
59 recorder_msgs::RollingRecorderGoal
goal;
70 action_client(nh,
"RosbagRollingRecord")
72 char dir_template[] =
"/tmp/rolling_recorder_testXXXXXX";
73 mkdtemp(dir_template);
77 rolling_recorder_options_.
write_directory = std::string(dir_template) +
"/";
84 boost::filesystem::path path(rolling_recorder_options_.
write_directory);
86 boost::filesystem::remove_all(path);
87 }
catch (std::exception& e) {
88 AWS_LOGSTREAM_INFO(__func__,
"Caught exception: " << e.what());
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();
111 std::string file_name = rolling_recorder_options_.
write_directory + GetFileNameForTimeStamp(time) + suffix;
113 file.open(file_name, std::ios::out);
120 std::vector<std::string> rosbags;
121 for (
int i = 0; i < num_bags; ++i) {
122 std::string suffix =
"_" + std::to_string(i) +
".bag";
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));
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;
145 file.open(file_name, std::ios::out);
147 rosbags.emplace_back(file_name);
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))) {
166 return AllFilesInFilesToDeleteHaveCountComparison(bags, [](
int count) ->
bool {
return count != 0;});
171 return AllFilesInFilesToDeleteHaveCountComparison(bags, [](
int count) ->
bool {
return count == 0;});
196 EXPECT_FALSE(rolling_recorder_.
ValidInputParam(rolling_recorder_options_));
206 EXPECT_FALSE(rolling_recorder_.
ValidInputParam(rolling_recorder_options_));
216 EXPECT_FALSE(rolling_recorder_.
ValidInputParam(rolling_recorder_options_));
222 GivenRollingRecorderInitialized();
224 bool message_received =
false;
230 message_received =
true;
233 recorder_msgs::RollingRecorderGoal goal;
234 auto gh = action_client.
sendGoal(goal, transition_call_back);
237 ASSERT_TRUE(message_received);
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));
253 GivenRollingRecorderInitialized();
254 file_uploader_msgs::UploadFilesGoal upload_goal;
255 upload_goal.files = GivenOldRosBags(3);
260 EXPECT_TRUE(FilesToDeleteContainsNoneOf(upload_goal.files));
263 EXPECT_TRUE(FilesToDeleteContainsAllOf(upload_goal.files));
266 int main(
int argc,
char ** argv)
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();
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)
void UpdateStatus(const RollingRecorderStatus &status)
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)
std::string write_directory
RollingRecorder rolling_recorder_
RollingRecorderOptions rolling_recorder_options_
void GivenRollingRecorderInitialized()
GoalHandle sendGoal(const Goal &goal, TransitionCallback transition_cb=TransitionCallback(), FeedbackCallback feedback_cb=FeedbackCallback())
ros::Duration bag_rollover_time
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)
bool ValidInputParam(RollingRecorderOptions rolling_recorder_options)
ROSCPP_DECL void shutdown()
ros::Duration max_record_time
boost::posix_time::ptime toBoost() const
ros::AsyncSpinner executor