19 #include <boost/filesystem.hpp> 22 #include <recorder_msgs/RollingRecorderAction.h> 29 #include <aws/core/utils/logging/LogMacros.h> 37 action_server_(node_handle_,
"RosbagRollingRecord", false),
38 upload_request_data_(
std::make_shared<
UploadRequestData>(
"/s3_file_uploader/UploadFiles", true)) {}
42 AWS_LOG_ERROR(__func__,
"bag_rollover_time must be a positive integer.");
46 AWS_LOG_ERROR(__func__,
"max_record_time must be a positive integer.");
50 AWS_LOG_ERROR(__func__,
"bag_rollover_time cannot be greater than max_record_time.");
54 AWS_LOG_ERROR(__func__,
"upload_timeout_s must be a positive number.");
67 [
this]()->std::vector<std::string>{
74 std::shared_ptr<UploadRequestData> data_ptr = data_weak_ptr.lock();
75 if (
nullptr == data_ptr) {
80 .rolling_recorder_options = data_ptr->rolling_recorder_options_,
81 .rosbag_uploader_action_client = data_ptr->rosbag_uploader_action_client_,
82 .action_server_busy = data_ptr->action_server_busy_,
83 .recorder_status = &data_ptr->recorder_status_
101 AWS_LOG_DEBUG(__func__,
"Getting ros bags to delete");
102 boost::filesystem::path dir_path(
upload_request_data_->rolling_recorder_options_.write_directory);
103 std::vector<std::string> delete_files;
104 boost::system::error_code ec;
105 for (boost::filesystem::directory_iterator itr(dir_path, ec);
106 itr != boost::filesystem::directory_iterator(); ++itr) {
107 if (ec.value() != 0) {
108 AWS_LOGSTREAM_WARN(__func__,
"boost::filesystem::directory_iterator errored with message: " << ec.message());
111 if (itr->path().extension().string() !=
".bag") {
114 const auto & file_path = itr->path().string();
116 if (file_paths.end() != std::find(file_paths.begin(), file_paths.end(), file_path)) {
117 AWS_LOGSTREAM_DEBUG(__func__,
"Skipping deletion of upload candidate: " << file_path);
120 AWS_LOGSTREAM_DEBUG(__func__,
"Checking path: " << file_path);
122 AWS_LOGSTREAM_DEBUG(__func__,
"Bag start time is: "<< bag_start_time);
125 AWS_LOGSTREAM_DEBUG(__func__,
"Marking file for deletion: " << file_path);
126 delete_files.emplace_back(file_path);
void UpdateStatus(const RollingRecorderStatus &status)
ros::Time GetRosBagStartTime(const std::string &file_path)
Get the time a rosbag started.
void registerGoalCallback(boost::function< void(GoalHandle)> cb)
void InitializeRollingRecorder()
ros::Duration bag_rollover_time
GoalHandleT & goal_handle
std::vector< std::string > GetRosBagsToDelete() const
std::shared_ptr< UploadRequestData > upload_request_data_
std::unique_ptr< Utils::PeriodicFileDeleter > periodic_file_deleter_
bool ValidInputParam(RollingRecorderOptions rolling_recorder_options)
ros::Duration max_record_time
static void RollingRecorderRosbagUpload(const RollingRecorderRosbagUploadRequest< GoalHandleT, UploadClientT > &req)
RollingRecorderActionServer action_server_