Program Listing for File Delivery.hpp

Return to documentation for file (/tmp/ws/src/rmf_task/rmf_task/include/rmf_task/requests/Delivery.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__REQUESTS__DELIVERY_HPP
#define RMF_TASK__REQUESTS__DELIVERY_HPP

#include <chrono>
#include <string>
#include <optional>

#include <rmf_traffic/Time.hpp>
#include <rmf_traffic/agv/Planner.hpp>

#include <rmf_battery/MotionPowerSink.hpp>
#include <rmf_battery/DevicePowerSink.hpp>

#include <rmf_task/State.hpp>
#include <rmf_task/Request.hpp>
#include <rmf_task/Estimate.hpp>
#include <rmf_task/Payload.hpp>

namespace rmf_task {
namespace requests {

//==============================================================================
class Delivery
{
public:

  // Forward declare the Model for this request
  class Model;

  class Description : public Task::Description
  {
  public:

    using Start = rmf_traffic::agv::Planner::Start;

    static Task::ConstDescriptionPtr make(
      std::size_t pickup_waypoint,
      rmf_traffic::Duration pickup_duration,
      std::size_t dropoff_waypoint,
      rmf_traffic::Duration dropoff_duration,
      Payload payload,
      std::string pickup_from_dispenser = "",
      std::string dropoff_to_ingestor = "");

    // Documentation inherited
    Task::ConstModelPtr make_model(
      rmf_traffic::Time earliest_start_time,
      const Parameters& parameters) const final;

    // Documentation inherited
    Info generate_info(
      const State& initial_state,
      const Parameters& parameters) const final;

    std::size_t pickup_waypoint() const;

    std::string pickup_from_dispenser() const;

    rmf_traffic::Duration pickup_wait() const;

    std::size_t dropoff_waypoint() const;

    std::string dropoff_to_ingestor() const;

    rmf_traffic::Duration dropoff_wait() const;

    const Payload& payload() const;

    class Implementation;
  private:
    Description();
    rmf_utils::impl_ptr<Implementation> _pimpl;
  };

  static ConstRequestPtr make(
    std::size_t pickup_waypoint,
    rmf_traffic::Duration pickup_wait,
    std::size_t dropoff_waypoint,
    rmf_traffic::Duration dropoff_wait,
    Payload payload,
    const std::string& id,
    rmf_traffic::Time earliest_start_time,
    ConstPriorityPtr priority = nullptr,
    bool automatic = false,
    std::string pickup_from_dispenser = "",
    std::string dropoff_to_ingestor = "");

  static ConstRequestPtr make(
    std::size_t pickup_waypoint,
    rmf_traffic::Duration pickup_wait,
    std::size_t dropoff_waypoint,
    rmf_traffic::Duration dropoff_wait,
    Payload payload,
    const std::string& id,
    rmf_traffic::Time earliest_start_time,
    const std::string& requester,
    rmf_traffic::Time request_time,
    ConstPriorityPtr priority = nullptr,
    bool automatic = false,
    std::string pickup_from_dispenser = "",
    std::string dropoff_to_ingestor = "");
};

} // namespace requests
} // namespace rmf_task

#endif // RMF_TASK__REQUESTS__DELIVERY_HPP