18 #include <aws/core/utils/logging/LogMacros.h> 31 constexpr
char kNodeName[] =
"rosbag_rolling_recorder";
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";
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;
48 int main(
int argc,
char* argv[])
51 Aws::Utils::Logging::InitializeAWSLogging(Aws::MakeShared<Aws::Utils::Logging::AWSROSLogger>(kNodeName));
54 auto parameter_reader = std::make_shared<Aws::Client::Ros1NodeParameterReader>();
57 int bag_rollover_time_input;
58 if (Aws::AwsError::AWS_ERR_OK == parameter_reader->ReadParam(
Aws::Client::ParameterPath(kBagRolloverTimeParameter), bag_rollover_time_input)) {
65 int max_record_time_input;
66 if (Aws::AwsError::AWS_ERR_OK == parameter_reader->ReadParam(
Aws::Client::ParameterPath(kMaxRecordTimeParameter), max_record_time_input)) {
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.");
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();
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;
103 AWS_LOG_INFO(__func__,
"Starting rolling recorder node.");
109 options.
split =
true;
113 if (topics_to_record.empty()) {
117 options.
topics = std::move(topics_to_record);
125 AWS_LOG_INFO(__func__,
"Finishing rolling recorder node.");
127 AWS_LOG_ERROR(__func__,
"Failed to initialize rolling recorder. Shutting down.");
133 AWS_LOG_ERROR(__func__,
"Failed to access rosbag write directory. Shutting down.");
137 Aws::Utils::Logging::ShutdownAWSLogging();
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)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string write_directory
ros::Duration bag_rollover_time
uint64_t min_free_space_mib
std::string min_space_str
virtual void spin(CallbackQueue *queue=0)
std::vector< std::string > topics
ROSCPP_DECL void shutdown()
ros::Duration max_record_time
ros::Duration max_duration
int main(int argc, char *argv[])