Program Listing for File DispatchState.hpp

Return to documentation for file (include/rmf_task_ros2/DispatchState.hpp)

/*
 * Copyright (C) 2020 Open Source Robotics Foundation
 *
 * Licensed under the Apache License, Version 2.0 (the "License");
 * you may not use this file except in compliance with the License.
 * You may obtain a copy of the License at
 *
 *     http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS,
 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 * See the License for the specific language governing permissions and
 * limitations under the License.
 *
*/

#ifndef RMF_TASK_ROS2__DISPATCH_STATE_HPP
#define RMF_TASK_ROS2__DISPATCH_STATE_HPP

#include <unordered_map>
#include <memory>
#include <optional>

#include <rmf_traffic_ros2/Time.hpp>
#include <rmf_task_msgs/msg/dispatch_state.hpp>

#include <nlohmann/json.hpp>

namespace rmf_task_ros2 {

//==============================================================================
using TaskID = std::string;

//==============================================================================
struct DispatchState
{
  using Msg = rmf_task_msgs::msg::DispatchState;

  enum class Status : uint8_t
  {
    Queued = Msg::STATUS_QUEUED,

    Selected = Msg::STATUS_SELECTED,

    Dispatched = Msg::STATUS_DISPATCHED,

    FailedToAssign = Msg::STATUS_FAILED_TO_ASSIGN,

    CanceledInFlight = Msg::STATUS_CANCELED_IN_FLIGHT
  };

  struct Assignment
  {
    std::string fleet_name;
    std::string expected_robot_name;
  };

  std::string task_id;

  rmf_traffic::Time submission_time;

  Status status = Status::Queued;

  std::optional<Assignment> assignment;

  std::vector<nlohmann::json> errors;

  nlohmann::json request;

  DispatchState(std::string task_id, rmf_traffic::Time submission_time);
};

using DispatchStatePtr = std::shared_ptr<DispatchState>;

//==============================================================================
std::string status_to_string(DispatchState::Status status);

//==============================================================================
rmf_task_msgs::msg::Assignment convert(
  const std::optional<DispatchState::Assignment>& assignment);

//==============================================================================
rmf_task_msgs::msg::DispatchState convert(const DispatchState& state);

} // namespace rmf_task_ros2

#endif // RMF_TASK_ROS2__DISPATCH_STATE_HPP