void HandleRecorderUploadResult()

in rosbag_cloud_recorders/include/rosbag_cloud_recorders/utils/s3_client_utils.h [91:132]


void HandleRecorderUploadResult(
  GoalHandleT& goal_handle,
  const SimpleClientGoalStateT& end_state,
  bool upload_finished,
  RecorderResultT& recorder_result)
{
  // Getting the Feedback type from the type of the first arugment to GoalHandleT::publishFeedback()
  // because GoalHandleT::Feedback is a private typedef
  using FuncType = decltype(&GoalHandleT::publishFeedback);
  using FuncArgsType = typename boost::function_types::parameter_types<FuncType>;
  using ArgCrefType = typename boost::mpl::at_c<FuncArgsType, 1>::type;
  using ArgConstType = typename boost::remove_reference<ArgCrefType>::type;
  using ArgType = typename boost::remove_const<ArgConstType>::type;
  ArgType recorder_feedback;
  recorder_msgs::RecorderStatus recording_status;
  Utils::GenerateFeedback(
    recorder_msgs::RecorderStatus::COMPLETE,
    ros::Time::now(),
    recorder_feedback,
    recording_status);
  goal_handle.publishFeedback(recorder_feedback);

  std::string msg;
  if (!upload_finished) {
    msg = "File Uploader timed out.";
    GenerateResult(recorder_msgs::RecorderResult::UPLOADER_TIMEOUT, msg, recorder_result);
    goal_handle.setAborted(recorder_result, msg);
    AWS_LOG_WARN(__func__, msg.c_str());
    return;
  }
  if (end_state != actionlib::SimpleClientGoalState::StateEnum::SUCCEEDED) {
    msg = "Upload failed with message: " + end_state.getText();
    GenerateResult(recorder_msgs::RecorderResult::DEPENDENCY_FAILURE, msg, recorder_result);
    goal_handle.setAborted(recorder_result, msg);
    AWS_LOG_ERROR(__func__, msg.c_str());
  } else {
    msg = "Upload Succeeded";
    GenerateResult(recorder_msgs::RecorderResult::SUCCESS, msg, recorder_result);
    goal_handle.setSucceeded(recorder_result, msg);
    AWS_LOG_INFO(__func__, msg.c_str());
  }
}