rolling_recorder.h
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 #pragma once
16 
17 #include <string>
18 #include <vector>
19 #include <atomic>
20 #include <ros/ros.h>
21 
22 #include <recorder_msgs/RollingRecorderAction.h>
23 #include <file_uploader_msgs/UploadFilesAction.h>
24 #include <file_uploader_msgs/UploadFilesGoal.h>
29 
30 namespace Aws
31 {
32 namespace Rosbag
33 {
34 
37 
38 // Contains option for deleting the rosbag after upload
40 {
41  uint64_t min_free_space_mib {0}; // minimum free disk space in mebibytes
42  std::string write_directory;
43  double upload_timeout_s {0};
46 };
47 
49 public:
50  virtual void SetUploadGoal(const file_uploader_msgs::UploadFilesGoal & goal)
51  {
52  current_upload_goal_ = goal;
53  }
54 
55  const file_uploader_msgs::UploadFilesGoal & GetUploadGoal() const
56  {
57  return current_upload_goal_;
58  }
59 
60 private:
61  file_uploader_msgs::UploadFilesGoal current_upload_goal_;
62 };
63 
68 {
69 public:
70  explicit RollingRecorder();
71  RollingRecorder(const RollingRecorder & other) = delete;
72  RollingRecorder(RollingRecorder && other) = delete;
73  RollingRecorder & operator=(const RollingRecorder & other) = delete;
74  RollingRecorder & operator=(RollingRecorder && other) = delete;
75  virtual ~RollingRecorder() = default;
76 
81  std::vector<std::string> GetRosBagsToDelete() const;
82 
86  void UpdateStatus(const RollingRecorderStatus & status);
87 
91  bool ValidInputParam(RollingRecorderOptions rolling_recorder_options);
92 
96  bool InitializeRollingRecorder(RollingRecorderOptions rolling_recorder_options);
97 
98 private:
100  UploadRequestData(const std::string & client_name, bool spin_thread)
101  : rosbag_uploader_action_client_(client_name, spin_thread), action_server_busy_(false) {}
102 
105  std::atomic<bool> action_server_busy_;
107  };
108 
109  void StartOldRosBagsPeriodicRemoval();
110  void InitializeRollingRecorder();
111 
114  std::shared_ptr<UploadRequestData> upload_request_data_;
115  std::unique_ptr<Utils::PeriodicFileDeleter> periodic_file_deleter_;
116 };
117 
118 } // namespace Rosbag
119 } // namespace Aws
file_uploader_msgs::UploadFilesGoal current_upload_goal_
UploadFilesActionSimpleClient rosbag_uploader_action_client_
const file_uploader_msgs::UploadFilesGoal & GetUploadGoal() const
std::shared_ptr< UploadRequestData > upload_request_data_
UploadRequestData(const std::string &client_name, bool spin_thread)
virtual void SetUploadGoal(const file_uploader_msgs::UploadFilesGoal &goal)
std::unique_ptr< Utils::PeriodicFileDeleter > periodic_file_deleter_
RollingRecorderActionServer action_server_


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