in rosbag_cloud_recorders/src/duration_recorder/main.cpp [46:92]
int main(int argc, char* argv[])
{
ros::init(argc, argv, kNodeName);
Aws::Utils::Logging::InitializeAWSLogging(
Aws::MakeShared<Aws::Utils::Logging::AWSROSLogger>(kNodeName));
Aws::Rosbag::DurationRecorderOptions duration_recorder_options;
auto parameter_reader = std::make_shared<Aws::Client::Ros1NodeParameterReader>();
int min_free_space;
if (Aws::AwsError::AWS_ERR_OK == parameter_reader->ReadParam(Aws::Client::ParameterPath(kMinFreeSpaceParameter), min_free_space)) {
if (min_free_space < 0) {
AWS_LOG_ERROR(__func__, "min_free_disk_space must be a positive integer.");
return EXIT_FAILURE;
}
duration_recorder_options.min_free_space_mib = min_free_space;
} else {
duration_recorder_options.min_free_space_mib = kMinFreeSpaceDefaultInMebibytes;
}
std::string write_dir_input;
if (Aws::AwsError::AWS_ERR_OK != parameter_reader->ReadParam(Aws::Client::ParameterPath(kWriteDirectoryParameter), write_dir_input)) {
write_dir_input = kWriteDirectoryDefault;
}
if (Aws::AwsError::AWS_ERR_OK != parameter_reader->ReadParam(Aws::Client::ParameterPath(kUploadTimeoutParameter), duration_recorder_options.upload_timeout_s)) {
duration_recorder_options.upload_timeout_s = kUploadTimeoutDefaultInSeconds;
}
if (Aws::AwsError::AWS_ERR_OK != parameter_reader->ReadParam(Aws::Client::ParameterPath(kDeleteBagsAfterUploadParameter), duration_recorder_options.delete_bags_after_upload)) {
duration_recorder_options.delete_bags_after_upload = kDeleteBagsAfterUploadDefault;
}
std::string write_dir;
if (Aws::Rosbag::Utils::ExpandAndCreateDir(write_dir_input, write_dir)) {
duration_recorder_options.write_directory = write_dir;
AWS_LOG_INFO(__func__, "Starting duration recorder");
Aws::Rosbag::DurationRecorder duration_recorder(duration_recorder_options);
ros::MultiThreadedSpinner spinner(2);
spinner.spin();
} else {
AWS_LOG_ERROR(__func__, "Failed to access rosbag write directory. Shutting down.");
return EXIT_FAILURE;
}
Aws::Utils::Logging::ShutdownAWSLogging();
return EXIT_SUCCESS;
}