28 #include <file_uploader_msgs/UploadFilesAction.h> 29 #include <recorder_msgs/DurationRecorderAction.h> 31 #include <aws/core/utils/logging/LogMacros.h> 45 template<
typename GoalHandleT,
typename UploadClientT>
51 const auto & goal = goal_handle.getGoal();
53 std::stringstream msg;
54 msg <<
"Goal rejected. Invalid record duration given: " << goal->duration;
55 recorder_msgs::DurationRecorderResult result;
57 goal_handle.setRejected(result, result.result.message);
58 AWS_LOG_INFO(__func__, result.result.message.c_str());
67 UploadClientT& upload_client,
68 GoalHandleT& goal_handle)
71 static auto current_function = __func__;
74 AWS_LOG_INFO(__func__,
"Goal received");
76 const std::string msg =
"Rejecting goal since recorder already active";
77 recorder_msgs::DurationRecorderResult result;
79 goal_handle.setRejected(result, msg);
80 AWS_LOG_INFO(__func__, msg.c_str());
89 const auto & goal = goal_handle.getGoal();
94 if (goal->topics_to_record.empty()) {
98 options.
topics = goal->topics_to_record;
102 auto run_result = rosbag_recorder.
Run(
104 [goal_handle, time_of_goal_received]()
mutable 106 goal_handle.setAccepted();
107 AWS_LOG_INFO(current_function,
"Goal accepted");
109 recorder_msgs::DurationRecorderFeedback recorder_feedback;
110 recorder_msgs::RecorderStatus recording_status;
112 recorder_msgs::RecorderStatus::RECORDING,
113 time_of_goal_received,
116 goal_handle.publishFeedback(recorder_feedback);
118 [goal_handle, duration_recorder_options, time_of_goal_received, &upload_client](
int exit_code)
mutable 120 recorder_msgs::DurationRecorderResult result;
121 if (exit_code != 0) {
122 const std::string msg =
"Rosbag recorder encountered errors.";
124 goal_handle.setAborted(result, msg);
125 AWS_LOG_INFO(current_function,
"Recorder finished with non zero exit code, aborting goal");
129 recorder_msgs::DurationRecorderFeedback recorder_feedback;
130 recorder_msgs::RecorderStatus recording_status;
132 recorder_msgs::RecorderStatus::PREPARING_UPLOAD,
136 goal_handle.publishFeedback(recorder_feedback);
142 return time_of_goal_received < rosbag.getBeginTime();
146 bool upload_finished =
Utils::UploadFiles(goal_handle, duration_recorder_options.upload_timeout_s, upload_client, ros_bags_to_upload);
150 if (duration_recorder_options.delete_bags_after_upload) {
152 recorder_msgs::RecorderStatus::CLEANUP,
156 goal_handle.publishFeedback(recorder_feedback);
157 for (
const std::string & bag_file_name : upload_client.getResult()->files_uploaded) {
158 AWS_LOG_INFO(current_function,
"Bag file named: %s was uploaded to S3 and is now being deleted locally.", bag_file_name.c_str());
166 recorder_msgs::DurationRecorderResult result;
167 result.result.result = recorder_msgs::RecorderResult::INTERNAL_ERROR;
168 goal_handle.setRejected(result,
"Rejecting result, DurationRecorder already handling goal.");
174 goal_handle.setCanceled();
virtual RosbagRecorderRunResult Run(const RecorderOptions &recorder_options, const std::function< void()> &pre_record=nullptr, const std::function< void(int)> &post_record=nullptr)
virtual bool IsActive() const
actionlib::ActionServer< recorder_msgs::DurationRecorderAction > DurationRecorderActionServer
uint64_t min_free_space_mib
std::vector< std::string > GetRosbagsToUpload(const std::string &write_directory, const std::function< bool(rosbag::View &)> &select_file)
Aws::Rosbag::RecorderErrorCode DeleteFile(const std::string &file_path)
delete a file
static void DurationRecorderStart(Utils::RosbagRecorder< Utils::Recorder > &rosbag_recorder, const DurationRecorderOptions &duration_recorder_options, UploadClientT &upload_client, GoalHandleT &goal_handle)
std::string write_directory
std::string min_space_str
bool UploadFiles(GoalHandleT &goal_handle, const double upload_time_out, UploadClientT &upload_client, std::vector< std::string > &ros_bags_to_upload)
static bool ValidateGoal(GoalHandleT &goal_handle)
static void CancelDurationRecorder(GoalHandleT &goal_handle)
void GenerateResult(uint8_t stage, std::string message, RecorderResultT &recorder_result)
std::vector< std::string > topics
ros::Duration max_duration
void HandleRecorderUploadResult(GoalHandleT &goal_handle, const SimpleClientGoalStateT &end_state, bool upload_finished, RecorderResultT &recorder_result)
void GenerateFeedback(uint8_t stage, ros::Time time_of_feedback, RecorderFeedbackT &recorder_feedback, RecorderStatusT &recording_status)
ROSTIME_DECL const Duration DURATION_MAX