Program Listing for File CentralizedNegotiation.hpp

Return to documentation for file (/tmp/ws/src/rmf_traffic/rmf_traffic/include/rmf_traffic/agv/CentralizedNegotiation.hpp)

/*
 * Copyright (C) 2022 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_TRAFFIC__AGV__CENTRALIZEDNEGOTIATION_HPP
#define RMF_TRAFFIC__AGV__CENTRALIZEDNEGOTIATION_HPP

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

namespace rmf_traffic {
namespace agv {

//==============================================================================
class CentralizedNegotiation
{
public:

  class Agent
  {
  public:

    Agent(
      schedule::ParticipantId id,
      Plan::Start start,
      Plan::Goal goal,
      std::shared_ptr<const Planner> planner,
      std::optional<SimpleNegotiator::Options> options = std::nullopt);

    Agent(
      schedule::ParticipantId id,
      std::vector<Plan::Start> starts,
      Plan::Goal goal,
      std::shared_ptr<const Planner> planner,
      std::optional<SimpleNegotiator::Options> options = std::nullopt);

    schedule::ParticipantId id() const;

    Agent& id(schedule::ParticipantId value);

    const std::vector<Plan::Start>& starts() const;

    Agent& starts(std::vector<Plan::Start> values);

    const Plan::Goal& goal() const;

    Agent& goal(Plan::Goal value);

    const std::shared_ptr<const Planner>& planner() const;

    Agent& planner(std::shared_ptr<const Planner> value);

    const std::optional<SimpleNegotiator::Options>& options() const;

    Agent& options(std::optional<SimpleNegotiator::Options> value);

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

  using Proposal = std::unordered_map<schedule::ParticipantId, Plan>;

  class Result
  {
  public:

    const std::optional<Proposal>& proposal() const;

    const std::unordered_set<schedule::ParticipantId>& blockers() const;

    const std::vector<std::string>& log() const;

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

  CentralizedNegotiation(std::shared_ptr<const schedule::Viewer> viewer);

  const std::shared_ptr<const schedule::Viewer>& viewer() const;

  CentralizedNegotiation& viewer(std::shared_ptr<const schedule::Viewer> v);

  CentralizedNegotiation& optimal(bool on = true);

  CentralizedNegotiation& log(bool on = true);

  CentralizedNegotiation& print(bool on = true);

  Result solve(const std::vector<Agent>& agents) const;

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

} // namespace agv
} // namespace rmf_traffic

#endif // RMF_TRAFFIC__AGV__CENTRALIZEDNEGOTIATION_HPP