rolling_recorder/main.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 #include <string>
16 
17 #include <ros/ros.h>
18 #include <aws/core/utils/logging/LogMacros.h>
22 
27 
28 namespace
29 {
30 
31 constexpr char kNodeName[] = "rosbag_rolling_recorder";
32 
33 constexpr char kBagRolloverTimeParameter[] = "bag_rollover_time";
34 constexpr char kMaxRecordTimeParameter[] = "max_record_time";
35 constexpr char kMinFreeSpaceParameter[] = "min_free_disk_space";
36 constexpr char kTopicsToRecordParameter[] = "topics_to_record";
37 constexpr char kWriteDirectoryParameter[] = "write_directory";
38 constexpr char kUploadTimeoutParameter[] = "upload_timeout";
39 
40 constexpr uint32_t kBagRolloverTimeDefaultInSeconds = 30;
41 constexpr uint32_t kMaxRecordTimeDefaultInSeconds = 300;
42 constexpr uint64_t kMinFreeSpaceDefaultInMebibytes = 1024;
43 constexpr char kWriteDirectoryDefault[] = "~/.ros/rr_rosbag_uploader/";
44 constexpr uint32_t kTimeOutDefaultInSeconds = 3600;
45 
46 } // namespace
47 
48 int main(int argc, char* argv[])
49 {
50  ros::init(argc, argv, kNodeName);
51  Aws::Utils::Logging::InitializeAWSLogging(Aws::MakeShared<Aws::Utils::Logging::AWSROSLogger>(kNodeName));
52 
53  Aws::Rosbag::RollingRecorderOptions rolling_recorder_options;
54  auto parameter_reader = std::make_shared<Aws::Client::Ros1NodeParameterReader>();
55 
56  // Set bag_rollover_time
57  int bag_rollover_time_input;
58  if (Aws::AwsError::AWS_ERR_OK == parameter_reader->ReadParam(Aws::Client::ParameterPath(kBagRolloverTimeParameter), bag_rollover_time_input)) {
59  rolling_recorder_options.bag_rollover_time = ros::Duration(bag_rollover_time_input);
60  } else {
61  rolling_recorder_options.bag_rollover_time = ros::Duration(kBagRolloverTimeDefaultInSeconds);
62  }
63 
64  // Set max_record_time
65  int max_record_time_input;
66  if (Aws::AwsError::AWS_ERR_OK == parameter_reader->ReadParam(Aws::Client::ParameterPath(kMaxRecordTimeParameter), max_record_time_input)) {
67  rolling_recorder_options.max_record_time = ros::Duration(max_record_time_input);
68  } else {
69  rolling_recorder_options.max_record_time = ros::Duration(kMaxRecordTimeDefaultInSeconds);
70  }
71 
72  // Set min_free_disk_space
73  int min_free_space;
74  if (Aws::AwsError::AWS_ERR_OK == parameter_reader->ReadParam(Aws::Client::ParameterPath(kMinFreeSpaceParameter), min_free_space)) {
75  if (min_free_space < 0) {
76  AWS_LOG_ERROR(__func__, "min_free_disk_space must be a positive integer.");
77  return EXIT_FAILURE;
78  }
79  rolling_recorder_options.min_free_space_mib = min_free_space;
80  } else {
81  rolling_recorder_options.min_free_space_mib = kMinFreeSpaceDefaultInMebibytes;
82  }
83 
84  // Set topics_to_record
85  std::vector<std::string> topics_to_record;
86  if (Aws::AwsError::AWS_ERR_OK != parameter_reader->ReadParam(Aws::Client::ParameterPath(kTopicsToRecordParameter), topics_to_record)) {
87  AWS_LOG_INFO(__func__, "Failed to load topics to record preference, defaulting to all topics.");
88  topics_to_record.clear();
89  }
90 
91  // Set write_directory
92  std::string write_directory_input;
93  if (Aws::AwsError::AWS_ERR_OK != parameter_reader->ReadParam(Aws::Client::ParameterPath(kWriteDirectoryParameter), write_directory_input)) {
94  write_directory_input = kWriteDirectoryDefault;
95  }
96 
97  // Set operation time out in seconds
98  if (Aws::AwsError::AWS_ERR_OK != parameter_reader->ReadParam(Aws::Client::ParameterPath(kUploadTimeoutParameter), rolling_recorder_options.upload_timeout_s)) {
99  rolling_recorder_options.upload_timeout_s = kTimeOutDefaultInSeconds;
100  }
101 
102  if (Aws::Rosbag::Utils::ExpandAndCreateDir(write_directory_input, rolling_recorder_options.write_directory)) {
103  AWS_LOG_INFO(__func__, "Starting rolling recorder node.");
105  Aws::Rosbag::RollingRecorder rolling_recorder;
106 
107  if (rolling_recorder.InitializeRollingRecorder(rolling_recorder_options)) {
109  options.split = true;
110  options.max_duration = rolling_recorder_options.bag_rollover_time;
111  options.min_space = 1024 * 1024 * rolling_recorder_options.min_free_space_mib; // mebibytes to bytes
112  options.min_space_str = std::to_string(rolling_recorder_options.min_free_space_mib) + 'M';
113  if (topics_to_record.empty()) {
114  options.record_all = true;
115  } else {
116  options.record_all = false;
117  options.topics = std::move(topics_to_record);
118  }
119  options.prefix = rolling_recorder_options.write_directory;
120  rosbag_recorder.Run(options, nullptr, [](int /*exit_code*/) { ros::shutdown(); });
121 
123  spinner.spin();
124 
125  AWS_LOG_INFO(__func__, "Finishing rolling recorder node.");
126  } else {
127  AWS_LOG_ERROR(__func__, "Failed to initialize rolling recorder. Shutting down.");
128  return EXIT_FAILURE;
129  }
130 
131  ros::shutdown();
132  } else {
133  AWS_LOG_ERROR(__func__, "Failed to access rosbag write directory. Shutting down.");
134  return EXIT_FAILURE;
135  }
136 
137  Aws::Utils::Logging::ShutdownAWSLogging();
138 
139  return EXIT_SUCCESS;
140 }
virtual RosbagRecorderRunResult Run(const RecorderOptions &recorder_options, const std::function< void()> &pre_record=nullptr, const std::function< void(int)> &post_record=nullptr)
bool InitializeRollingRecorder(RollingRecorderOptions rolling_recorder_options)
bool ExpandAndCreateDir(const std::string &dir, std::string &expanded_dir)
Definition: file_utils.cpp:57
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void spinner()
options
virtual void spin(CallbackQueue *queue=0)
std::vector< std::string > topics
Definition: recorder.h:122
ROSCPP_DECL void shutdown()
int main(int argc, char *argv[])


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