rolling_recorder_action_server_handler.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 
16 #pragma once
17 
19 #include <memory>
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>
27 #include <rosbag/bag.h>
28 #include <rosbag/view.h>
33 
34 namespace Aws {
35 namespace Rosbag {
36 
37 template<typename GoalHandleT, typename UploadClientT>
39  GoalHandleT & goal_handle;
42  std::atomic<bool> & action_server_busy;
44 };
45 
46 template<typename GoalHandleT, typename UploadClientT>
48 {
49 public:
52  ) {
53  AWS_LOG_INFO(__func__, "A new goal has been recieved by the goal action server");
54  bool expected_action_server_state = false;
55 
56  // Check if action server is currently processing another goal
57  if (std::atomic_compare_exchange_strong(&(req.action_server_busy),
58  &expected_action_server_state,
59  true)) {
60  ProcessRollingRecorderGoal(req);
61  req.action_server_busy = false; // Done processing goal, setting action server status to not busy
62  } else {
63  const std::string log_message = "Rejecting new goal. Rolling recorder is already processing a goal.";
64  recorder_msgs::RollingRecorderResult result;
65  Utils::GenerateResult(recorder_msgs::RecorderResult::INVALID_INPUT, log_message, result);
66  req.goal_handle.setRejected(result, log_message);
67  AWS_LOG_WARN(__func__, log_message.c_str());
68  }
69  }
70 
71 private:
74  ) {
75  recorder_msgs::RollingRecorderResult result;
76  ros::Time time_of_goal_received = ros::Time::now();
77 
78  // Accept incoming goal and start processing it
79  AWS_LOG_INFO(__func__, "Sending rosbag uploader goal to uploader action server.");
80  req.goal_handle.setAccepted();
81 
82  recorder_msgs::RollingRecorderFeedback recorder_feedback;
83  recorder_msgs::RecorderStatus recording_status;
85  recorder_msgs::RecorderStatus::PREPARING_UPLOAD,
86  time_of_goal_received,
87  recorder_feedback,
88  recording_status);
89  req.goal_handle.publishFeedback(recorder_feedback);
90  std::vector<std::string> rosbags_to_upload = Utils::GetRosbagsToUpload(req.rolling_recorder_options.write_directory,
91  [time_of_goal_received](rosbag::View& rosbag) -> bool
92  {
93  return time_of_goal_received >= rosbag.getBeginTime();
94  }
95  );
96  if (rosbags_to_upload.empty()) {
97  const std::string msg = "No rosbags found to upload.";
99  req.goal_handle.setSucceeded(result, msg);
100  AWS_LOG_INFO(__func__, msg.c_str());
101  return;
102  }
103 
104  auto goal = Utils::ConstructRosBagUploaderGoal(req.goal_handle.getGoal()->destination, rosbags_to_upload);
105  req.recorder_status->SetUploadGoal(goal);
106  req.rosbag_uploader_action_client.sendGoal(goal);
107 
109  recorder_msgs::RecorderStatus::UPLOADING,
110  ros::Time::now(),
111  recorder_feedback,
112  recording_status);
113  req.goal_handle.publishFeedback(recorder_feedback);
114  bool upload_finished = req.rosbag_uploader_action_client.waitForResult(ros::Duration(req.rolling_recorder_options.upload_timeout_s));
115 
116  Utils::HandleRecorderUploadResult(req.goal_handle, req.rosbag_uploader_action_client.getState(), upload_finished, result);
117  req.recorder_status->SetUploadGoal(file_uploader_msgs::UploadFilesGoal());
118  }
119 };
120 
121 } // namespace Rosbag
122 } // namespace Aws
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)
Definition: file_utils.cpp:181
file_uploader_msgs::UploadFilesGoal ConstructRosBagUploaderGoal(std::string destination, std::vector< std::string > &ros_bags_to_upload)
void GenerateResult(uint8_t stage, std::string message, RecorderResultT &recorder_result)
static Time now()
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)


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