Program Listing for File Task.hpp

Return to documentation for file (/tmp/ws/src/rmf_task/rmf_task/include/rmf_task/Task.hpp)

/*
 * Copyright (C) 2021 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__TASK_HPP
#define RMF_TASK__TASK_HPP

#include <rmf_task/Header.hpp>
#include <rmf_task/Phase.hpp>
#include <rmf_task/detail/Backup.hpp>
#include <rmf_task/detail/Resume.hpp>
#include <rmf_task/Constraints.hpp>
#include <rmf_task/Parameters.hpp>
#include <rmf_task/State.hpp>
#include <rmf_task/Estimate.hpp>
#include <rmf_task/Priority.hpp>

#include <rmf_traffic/Time.hpp>

#include <memory>
#include <optional>
#include <functional>

namespace rmf_task {

//==============================================================================
class Task
{
public:

  // Declarations
  class Booking;
  using ConstBookingPtr = std::shared_ptr<const Booking>;

  class Tag;
  using ConstTagPtr = std::shared_ptr<const Tag>;

  class Model;
  using ConstModelPtr = std::shared_ptr<const Model>;

  class Description;
  using ConstDescriptionPtr = std::shared_ptr<const Description>;

  class Active;
  using ActivePtr = std::shared_ptr<Active>;
};

//==============================================================================
class Task::Booking
{
public:

  Booking(
    std::string id,
    rmf_traffic::Time earliest_start_time,
    ConstPriorityPtr priority,
    bool automatic = false,
    const std::vector<std::string>& labels = {});

  Booking(
    std::string id,
    rmf_traffic::Time earliest_start_time,
    ConstPriorityPtr priority,
    const std::string& requester,
    rmf_traffic::Time request_time,
    bool automatic = false,
    const std::vector<std::string>& labels = {});

  const std::string& id() const;

  rmf_traffic::Time earliest_start_time() const;

  ConstPriorityPtr priority() const;

  std::optional<std::string> requester() const;

  std::optional<rmf_traffic::Time> request_time() const;

  // Returns true if this booking was automatically generated.
  bool automatic() const;

  std::vector<std::string> labels() const;

  class Implementation;
private:
  rmf_utils::impl_ptr<Implementation> _pimpl;
};

//==============================================================================
class Task::Tag
{
public:

  Tag(
    ConstBookingPtr booking_,
    Header header_);

  const ConstBookingPtr& booking() const;

  const Header& header() const;

  class Implementation;
private:
  rmf_utils::impl_ptr<Implementation> _pimpl;
};

//==============================================================================
class Task::Model
{
public:

  virtual std::optional<Estimate> estimate_finish(
    const State& initial_state,
    const Constraints& task_planning_constraints,
    const TravelEstimator& travel_estimator) const = 0;

  virtual rmf_traffic::Duration invariant_duration() const = 0;

  virtual ~Model() = default;
};

//==============================================================================
class Task::Description
{
public:

  virtual ConstModelPtr make_model(
    rmf_traffic::Time earliest_start_time,
    const Parameters& parameters) const = 0;

  struct Info
  {
    std::string category;
    std::string detail;
  };

  virtual Info generate_info(
    const State& initial_state,
    const Parameters& parameters) const = 0;

  // Virtual destructor
  virtual ~Description() = default;
};

//==============================================================================
class Task::Active
{
public:
  using Backup = detail::Backup;

  virtual Event::Status status_overview() const = 0;

  virtual bool finished() const = 0;

  virtual const std::vector<Phase::ConstCompletedPtr>&
  completed_phases() const = 0;

  virtual Phase::ConstActivePtr active_phase() const = 0;

  virtual std::optional<rmf_traffic::Time> active_phase_start_time() const = 0;

  virtual const std::vector<Phase::Pending>& pending_phases() const = 0;

  virtual const ConstTagPtr& tag() const = 0;

  virtual rmf_traffic::Duration estimate_remaining_time() const = 0;

  virtual Backup backup() const = 0;

  using Resume = detail::Resume;

  virtual Resume interrupt(std::function<void()> task_is_interrupted) = 0;

  // TODO(MXG): Should we have a pause() interface? It would be the same as
  // interrupt() except without the expectation that the robot will do any other
  // task before resuming.

  virtual void cancel() = 0;

  virtual void kill() = 0;

  virtual void skip(uint64_t phase_id, bool value = true) = 0;

  virtual void rewind(uint64_t phase_id) = 0;

  // Virtual destructor
  virtual ~Active() = default;

protected:

  static Resume make_resumer(std::function<void()> callback);
};

} // namespace rmf_task

#endif // RMF_TASK__TASK_HPP