Program Listing for File Auctioneer.hpp

Return to documentation for file (/tmp/ws/src/rmf_ros2/rmf_task_ros2/include/rmf_task_ros2/bidding/Auctioneer.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__BIDDING__AUCTIONEER_HPP
#define RMF_TASK_ROS2__BIDDING__AUCTIONEER_HPP

#include <queue>
#include <rclcpp/node.hpp>
#include <rmf_utils/impl_ptr.hpp>

#include <rmf_task_ros2/bidding/Response.hpp>

namespace rmf_task_ros2 {
namespace bidding {

//==============================================================================
class Auctioneer : public std::enable_shared_from_this<Auctioneer>
{
public:

  using BiddingResultCallback =
    std::function<
    void(
      const std::string& task_id,
      const std::optional<Response::Proposal> winner,
      const std::vector<std::string>& errors)>;

  class Evaluator
  {
  public:

    virtual std::optional<std::size_t> choose(
      const Responses& responses) const = 0;

    virtual ~Evaluator() = default;
  };

  using ConstEvaluatorPtr = std::shared_ptr<const Evaluator>;

  static std::shared_ptr<Auctioneer> make(
    const std::shared_ptr<rclcpp::Node>& node,
    BiddingResultCallback result_callback,
    ConstEvaluatorPtr evaluator);

  void request_bid(const BidNoticeMsg& bid_notice);

  void ready_for_next_bid();

  void set_evaluator(ConstEvaluatorPtr evaluator);

  class Implementation;

private:
  Auctioneer();
  rmf_utils::unique_impl_ptr<Implementation> _pimpl;
};

//==============================================================================
class LeastFleetDiffCostEvaluator : public Auctioneer::Evaluator
{
public:
  std::optional<std::size_t> choose(const Responses& responses) const final;
};

//==============================================================================
class LeastFleetCostEvaluator : public Auctioneer::Evaluator
{
public:
  std::optional<std::size_t> choose(const Responses& submissions) const final;
};

//==============================================================================
class QuickestFinishEvaluator : public Auctioneer::Evaluator
{
public:
  std::optional<std::size_t> choose(const Responses& submissions) const final;
};

} // namespace bidding
} // namespace rmf_task_ros2

#endif // RMF_TASK_ROS2__BIDDING__AUCTIONEER_HPP