s3_client_utils.h
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 
17 #include <boost/function_types/parameter_types.hpp>
18 #include <boost/typeof/std/utility.hpp>
19 
20 #include <file_uploader_msgs/UploadFilesAction.h>
21 
23 
24 namespace Aws
25 {
26 namespace Rosbag
27 {
28 namespace Utils
29 {
30 
31 file_uploader_msgs::UploadFilesGoal ConstructRosBagUploaderGoal(std::string destination,
32  std::vector<std::string> & ros_bags_to_upload);
33 
34 template<typename RecorderFeedbackT, typename RecorderStatusT>
36  uint8_t stage,
37  ros::Time time_of_feedback,
38  RecorderFeedbackT& recorder_feedback,
39  RecorderStatusT& recording_status)
40 {
41  recorder_feedback.started = time_of_feedback;
42  recording_status.stage = stage;
43  recorder_feedback.status = recording_status;
44 }
45 
46 template<typename GoalHandleT, typename UploadClientT>
48  GoalHandleT& goal_handle,
49  const double upload_time_out,
50  UploadClientT& upload_client,
51  std::vector<std::string>& ros_bags_to_upload)
52 {
53  AWS_LOG_INFO(__func__, "Uploading Files.");
54 
55  auto goal = Utils::ConstructRosBagUploaderGoal(goal_handle.getGoal()->destination, ros_bags_to_upload);
56  upload_client.sendGoal(goal);
57 
58  // Getting the Feedback type from the type of the first arugment to GoalHandleT::publishFeedback()
59  // because GoalHandleT::Feedback is a private typedef
60  using FuncType = decltype(&GoalHandleT::publishFeedback);
61  using FuncArgsType = typename boost::function_types::parameter_types<FuncType>;
62  using ArgCrefType = typename boost::mpl::at_c<FuncArgsType, 1>::type;
63  using ArgConstType = typename boost::remove_reference<ArgCrefType>::type;
64  using ArgType = typename boost::remove_const<ArgConstType>::type;
65  ArgType recorder_feedback;
66  recorder_msgs::RecorderStatus recording_status;
68  recorder_msgs::RecorderStatus::UPLOADING,
70  recorder_feedback,
71  recording_status);
72  goal_handle.publishFeedback(recorder_feedback);
73  bool upload_finished = true;
74  if (upload_time_out > 0) {
75  upload_finished = upload_client.waitForResult(ros::Duration(upload_time_out));
76  } else {
77  upload_finished = upload_client.waitForResult();
78  }
79 
80  return upload_finished;
81 }
82 
83 template<typename RecorderResultT>
84 void GenerateResult(uint8_t stage, std::string message, RecorderResultT& recorder_result)
85 {
86  recorder_result.result.result = stage;
87  recorder_result.result.message = std::move(message);
88 }
89 
90 template<typename GoalHandleT, typename SimpleClientGoalStateT, typename RecorderResultT>
92  GoalHandleT& goal_handle,
93  const SimpleClientGoalStateT& end_state,
94  bool upload_finished,
95  RecorderResultT& recorder_result)
96 {
97  // Getting the Feedback type from the type of the first arugment to GoalHandleT::publishFeedback()
98  // because GoalHandleT::Feedback is a private typedef
99  using FuncType = decltype(&GoalHandleT::publishFeedback);
100  using FuncArgsType = typename boost::function_types::parameter_types<FuncType>;
101  using ArgCrefType = typename boost::mpl::at_c<FuncArgsType, 1>::type;
102  using ArgConstType = typename boost::remove_reference<ArgCrefType>::type;
103  using ArgType = typename boost::remove_const<ArgConstType>::type;
104  ArgType recorder_feedback;
105  recorder_msgs::RecorderStatus recording_status;
107  recorder_msgs::RecorderStatus::COMPLETE,
108  ros::Time::now(),
109  recorder_feedback,
110  recording_status);
111  goal_handle.publishFeedback(recorder_feedback);
112 
113  std::string msg;
114  if (!upload_finished) {
115  msg = "File Uploader timed out.";
116  GenerateResult(recorder_msgs::RecorderResult::UPLOADER_TIMEOUT, msg, recorder_result);
117  goal_handle.setAborted(recorder_result, msg);
118  AWS_LOG_WARN(__func__, msg.c_str());
119  return;
120  }
121  if (end_state != actionlib::SimpleClientGoalState::StateEnum::SUCCEEDED) {
122  msg = "Upload failed with message: " + end_state.getText();
123  GenerateResult(recorder_msgs::RecorderResult::DEPENDENCY_FAILURE, msg, recorder_result);
124  goal_handle.setAborted(recorder_result, msg);
125  AWS_LOG_ERROR(__func__, msg.c_str());
126  } else {
127  msg = "Upload Succeeded";
129  goal_handle.setSucceeded(recorder_result, msg);
130  AWS_LOG_INFO(__func__, msg.c_str());
131  }
132 }
133 
134 } // namespace Utils
135 } // namespace Rosbag
136 } // namespace Aws
file_uploader_msgs::UploadFilesGoal ConstructRosBagUploaderGoal(std::string destination, std::vector< std::string > &ros_bags_to_upload)
bool UploadFiles(GoalHandleT &goal_handle, const double upload_time_out, UploadClientT &upload_client, std::vector< std::string > &ros_bags_to_upload)
void GenerateResult(uint8_t stage, std::string message, RecorderResultT &recorder_result)
static Time now()
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)


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