rolling_recorder.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2019 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 <string>
17 #include <vector>
18 
19 #include <boost/filesystem.hpp>
20 #include <ros/ros.h>
21 
22 #include <recorder_msgs/RollingRecorderAction.h>
26 
29 #include <aws/core/utils/logging/LogMacros.h>
30 
31 namespace Aws
32 {
33 namespace Rosbag
34 {
36  node_handle_("~"),
37  action_server_(node_handle_, "RosbagRollingRecord", false),
38  upload_request_data_(std::make_shared<UploadRequestData>("/s3_file_uploader/UploadFiles", true)) {}
39 
41  if (rolling_recorder_options.bag_rollover_time.toSec() <= 0) {
42  AWS_LOG_ERROR(__func__, "bag_rollover_time must be a positive integer.");
43  return false;
44  }
45  if (rolling_recorder_options.max_record_time.toSec() <= 0) {
46  AWS_LOG_ERROR(__func__, "max_record_time must be a positive integer.");
47  return false;
48  }
49  if (rolling_recorder_options.bag_rollover_time.toSec() > rolling_recorder_options.max_record_time.toSec()) {
50  AWS_LOG_ERROR(__func__, "bag_rollover_time cannot be greater than max_record_time.");
51  return false;
52  }
53  if (rolling_recorder_options.upload_timeout_s <= 0) {
54  AWS_LOG_ERROR(__func__, "upload_timeout_s must be a positive number.");
55  return false;
56  }
57  return true;
58 }
59 
61  upload_request_data_->rolling_recorder_options_ = std::move(rolling_recorder_options);
62  if (!ValidInputParam(upload_request_data_->rolling_recorder_options_)) {
63  return false;
64  }
65 
66  periodic_file_deleter_ = std::make_unique<Utils::PeriodicFileDeleter>(
67  [this]()->std::vector<std::string>{
68  return this->GetRosBagsToDelete();
69  },
70  upload_request_data_->rolling_recorder_options_.bag_rollover_time.toSec());
71 
72  std::weak_ptr<UploadRequestData> data_weak_ptr = upload_request_data_;
74  std::shared_ptr<UploadRequestData> data_ptr = data_weak_ptr.lock();
75  if (nullptr == data_ptr) {
76  return;
77  }
79  .goal_handle = goal_handle,
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_
84  };
86  });
87 
89  periodic_file_deleter_->Start();
90 
91  return true;
92 }
93 
95 {
96  upload_request_data_->recorder_status_ = status;
97 }
98 
99 std::vector<std::string> RollingRecorder::GetRosBagsToDelete() const
100 {
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());
109  break;
110  }
111  if (itr->path().extension().string() != ".bag") {
112  continue;
113  }
114  const auto & file_path = itr->path().string();
115  const auto & file_paths = upload_request_data_->recorder_status_.GetUploadGoal().files;
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);
118  continue;
119  }
120  AWS_LOGSTREAM_DEBUG(__func__, "Checking path: " << file_path);
121  auto bag_start_time = Utils::GetRosBagStartTime(file_path);
122  AWS_LOGSTREAM_DEBUG(__func__, "Bag start time is: "<< bag_start_time);
123  if (bag_start_time != ros::Time(0) && ros::Time::now() - bag_start_time >
124  upload_request_data_->rolling_recorder_options_.max_record_time) {
125  AWS_LOGSTREAM_DEBUG(__func__, "Marking file for deletion: " << file_path);
126  delete_files.emplace_back(file_path);
127  }
128  }
129  return delete_files;
130 }
131 
132 } // namespace Rosbag
133 } // namespace Aws
void UpdateStatus(const RollingRecorderStatus &status)
ros::Time GetRosBagStartTime(const std::string &file_path)
Get the time a rosbag started.
Definition: file_utils.cpp:119
void registerGoalCallback(boost::function< void(GoalHandle)> cb)
std::vector< std::string > GetRosBagsToDelete() const
std::shared_ptr< UploadRequestData > upload_request_data_
std::unique_ptr< Utils::PeriodicFileDeleter > periodic_file_deleter_
static Time now()
bool ValidInputParam(RollingRecorderOptions rolling_recorder_options)
static void RollingRecorderRosbagUpload(const RollingRecorderRosbagUploadRequest< GoalHandleT, UploadClientT > &req)
RollingRecorderActionServer action_server_


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