Program Listing for File EasyTrafficLight.hpp

Return to documentation for file (/tmp/ws/src/rmf_ros2/rmf_fleet_adapter/include/rmf_fleet_adapter/agv/EasyTrafficLight.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_FLEET_ADAPTER__AGV__EASYTRAFFICLIGHT_HPP
#define RMF_FLEET_ADAPTER__AGV__EASYTRAFFICLIGHT_HPP

#include <rmf_fleet_adapter/agv/Waypoint.hpp>
#include <rmf_traffic/schedule/ParticipantDescription.hpp>

namespace rmf_fleet_adapter {
namespace agv {

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

  void follow_new_path(const std::vector<Waypoint>& new_path);

  enum class MovingInstruction : uint8_t
  {
    MovingError = 0,

    ContinueAtNextCheckpoint,

    WaitAtNextCheckpoint,

    PauseImmediately
  };

  [[nodiscard]]
  MovingInstruction moving_from(
    std::size_t checkpoint,
    Eigen::Vector3d location);

  enum class WaitingInstruction : uint8_t
  {
    WaitingError = 0,

    Resume,

    Wait,
  };

  [[nodiscard]]
  WaitingInstruction waiting_at(std::size_t checkpoint);

  [[nodiscard]]
  WaitingInstruction waiting_after(
    std::size_t checkpoint,
    Eigen::Vector3d location);

  std::size_t last_reached() const;

  EasyTrafficLight& update_idle_location(
    std::string map_name,
    Eigen::Vector3d position);

  EasyTrafficLight& update_battery_soc(double battery_soc);

  EasyTrafficLight& replan();

  EasyTrafficLight& fleet_state_publish_period(
    std::optional<rmf_traffic::Duration> value);

  class Blocker
  {
  public:

    rmf_traffic::schedule::ParticipantId participant_id() const;

    const rmf_traffic::schedule::ParticipantDescription& description() const;

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

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

using EasyTrafficLightPtr = std::shared_ptr<EasyTrafficLight>;

} // namespace agv
} // namespace rmf_fleet_adapter

#endif // RMF_FLEET_ADAPTER__AGV__EASYTRAFFICLIGHT_HPP