20 #include <recorder_msgs/RollingRecorderAction.h> 22 #include <boost/filesystem.hpp> 24 #include <file_uploader_msgs/UploadFilesGoal.h> 25 #include <file_uploader_msgs/UploadFilesResult.h> 26 #include <aws/core/utils/logging/LogMacros.h> 37 template<
typename GoalHandleT,
typename UploadClientT>
46 template<
typename GoalHandleT,
typename UploadClientT>
53 AWS_LOG_INFO(__func__,
"A new goal has been recieved by the goal action server");
54 bool expected_action_server_state =
false;
58 &expected_action_server_state,
60 ProcessRollingRecorderGoal(req);
63 const std::string log_message =
"Rejecting new goal. Rolling recorder is already processing a goal.";
64 recorder_msgs::RollingRecorderResult result;
67 AWS_LOG_WARN(__func__, log_message.c_str());
75 recorder_msgs::RollingRecorderResult result;
79 AWS_LOG_INFO(__func__,
"Sending rosbag uploader goal to uploader action server.");
82 recorder_msgs::RollingRecorderFeedback recorder_feedback;
83 recorder_msgs::RecorderStatus recording_status;
85 recorder_msgs::RecorderStatus::PREPARING_UPLOAD,
86 time_of_goal_received,
93 return time_of_goal_received >= rosbag.getBeginTime();
96 if (rosbags_to_upload.empty()) {
97 const std::string msg =
"No rosbags found to upload.";
100 AWS_LOG_INFO(__func__, msg.c_str());
109 recorder_msgs::RecorderStatus::UPLOADING,
113 req.
goal_handle.publishFeedback(recorder_feedback);
117 req.
recorder_status->SetUploadGoal(file_uploader_msgs::UploadFilesGoal());
UploadClientT & rosbag_uploader_action_client
static void ProcessRollingRecorderGoal(const RollingRecorderRosbagUploadRequest< GoalHandleT, UploadClientT > &req)
std::vector< std::string > GetRosbagsToUpload(const std::string &write_directory, const std::function< bool(rosbag::View &)> &select_file)
GoalHandleT & goal_handle
const RollingRecorderOptions & rolling_recorder_options
file_uploader_msgs::UploadFilesGoal ConstructRosBagUploaderGoal(std::string destination, std::vector< std::string > &ros_bags_to_upload)
RollingRecorderStatus * recorder_status
void GenerateResult(uint8_t stage, std::string message, RecorderResultT &recorder_result)
std::atomic< bool > & action_server_busy
static void RollingRecorderRosbagUpload(const RollingRecorderRosbagUploadRequest< GoalHandleT, UploadClientT > &req)
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)