Program Listing for File Negotiation.hpp

Return to documentation for file (/tmp/ws/src/rmf_ros2/rmf_traffic_ros2/include/rmf_traffic_ros2/schedule/Negotiation.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_TRAFFIC_ROS2__SCHEDULE__NEGOTIATION_HPP
#define RMF_TRAFFIC_ROS2__SCHEDULE__NEGOTIATION_HPP

#include <rclcpp/node.hpp>

#include <rmf_traffic/schedule/Negotiator.hpp>
#include <rmf_traffic/schedule/Participant.hpp>
#include <rmf_traffic/schedule/Snapshot.hpp>

#include <rmf_utils/impl_ptr.hpp>

namespace rmf_traffic_ros2 {
namespace schedule {

//==============================================================================
class Negotiation
{
public:

  class Worker
  {
  public:

    virtual void schedule(std::function<void()> job) = 0;

    virtual ~Worker() = default;
  };

  Negotiation(
    rclcpp::Node& node,
    std::shared_ptr<const rmf_traffic::schedule::Snappable> viewer,
    std::shared_ptr<Worker> worker = nullptr);

  Negotiation& timeout_duration(rmf_traffic::Duration duration);

  rmf_traffic::Duration timeout_duration() const;

  using TableViewPtr = rmf_traffic::schedule::Negotiation::Table::ViewerPtr;
  using ResponderPtr = rmf_traffic::schedule::Negotiator::ResponderPtr;
  using StatusUpdateCallback =
    std::function<void (uint64_t conflict_version, TableViewPtr table_view)>;

  void on_status_update(StatusUpdateCallback cb);

  using StatusConclusionCallback =
    std::function<void (uint64_t conflict_version, bool success)>;

  void on_conclusion(StatusConclusionCallback cb);

  TableViewPtr table_view(
    uint64_t conflict_version,
    const std::vector<rmf_traffic::schedule::ParticipantId>& sequence) const;

  void set_retained_history_count(uint count);

  std::shared_ptr<void> register_negotiator(
    rmf_traffic::schedule::ParticipantId for_participant,
    std::unique_ptr<rmf_traffic::schedule::Negotiator> negotiator);

  std::shared_ptr<void> register_negotiator(
    rmf_traffic::schedule::ParticipantId for_participant,
    std::unique_ptr<rmf_traffic::schedule::Negotiator> negotiator,
    std::function<void()> on_negotiation_failure);

  std::shared_ptr<void> register_negotiator(
    rmf_traffic::schedule::ParticipantId for_participant,
    std::function<void(TableViewPtr view, ResponderPtr responder)> respond,
    std::function<void()> on_negotiation_failure = nullptr);

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

} // namespace schedule
} // namespace rmf_traffic_ros2

#endif // RMF_TRAFFIC_ROS2__SCHEDULE__NEGOTIATION_HPP