Program Listing for File RobotUpdateHandle.hpp

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

#include <rmf_traffic/Time.hpp>
#include <rmf_traffic/agv/Planner.hpp>
#include <rmf_utils/impl_ptr.hpp>
#include <rmf_utils/optional.hpp>

#include <rmf_traffic/schedule/Participant.hpp>

#include <Eigen/Geometry>
#include <nlohmann/json.hpp>

#include <vector>
#include <memory>
#include <functional>

namespace rmf_fleet_adapter {
namespace agv {

//==============================================================================
class RobotUpdateHandle
{
public:

  [[deprecated("Use replan() instead")]]
  void interrupted();

  void replan();

  void update_position(
    std::size_t waypoint,
    double orientation);

  void update_position(
    const Eigen::Vector3d& position,
    const std::vector<std::size_t>& lanes);

  void update_position(
    const Eigen::Vector3d& position,
    std::size_t target_waypoint);

  void update_position(
    const std::string& map_name,
    const Eigen::Vector3d& position,
    const double max_merge_waypoint_distance = 0.1,
    const double max_merge_lane_distance = 1.0,
    const double min_lane_length = 1e-8);

  void update_position(rmf_traffic::agv::Plan::StartSet position);

  RobotUpdateHandle& set_charger_waypoint(const std::size_t charger_wp);

  void update_battery_soc(const double battery_soc);

  void override_status(std::optional<std::string> status);

  RobotUpdateHandle& maximum_delay(
    rmf_utils::optional<rmf_traffic::Duration> value);

  rmf_utils::optional<rmf_traffic::Duration> maximum_delay() const;

  class ActionExecution
  {
  public:
    void update_remaining_time(rmf_traffic::Duration remaining_time_estimate);

    void underway(std::optional<std::string> text);

    void error(std::optional<std::string> text);

    void delayed(std::optional<std::string> text);

    void blocked(std::optional<std::string> text);

    void finished();

    bool okay() const;

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

  using ActionExecutor = std::function<void(
        const std::string& category,
        const nlohmann::json& description,
        ActionExecution execution)>;

  void set_action_executor(ActionExecutor action_executor);

  void submit_direct_request(
    nlohmann::json task_request,
    std::string request_id,
    std::function<void(nlohmann::json response)> receive_response);

  class Interruption
  {
  public:
    void resume(std::vector<std::string> labels);

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

  Interruption interrupt(
    std::vector<std::string> labels,
    std::function<void()> robot_is_interrupted);

  void cancel_task(
    std::string task_id,
    std::vector<std::string> labels,
    std::function<void(bool task_was_found)> on_cancellation);

  void kill_task(
    std::string task_id,
    std::vector<std::string> labels,
    std::function<void(bool task_was_found)> on_kill);

  enum class Tier
  {
    Info,

    Warning,

    Error
  };

  class IssueTicket
  {
  public:

    void resolve(nlohmann::json msg);

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

  IssueTicket create_issue(
    Tier tier, std::string category, nlohmann::json detail);

  // TODO(MXG): Should we offer a "clear_all_issues" function?

  void log_info(std::string text);

  void log_warning(std::string text);

  void log_error(std::string text);

  void enable_responsive_wait(bool value);

  class Implementation;

  class Unstable
  {
  public:
    bool is_commissioned() const;

    void decommission();

    void recommission();

    rmf_traffic::schedule::Participant* get_participant();

    void change_participant_profile(
      double footprint_radius,
      double vicinity_radius);

    void declare_holding(
      std::string on_map,
      Eigen::Vector3d at_position,
      rmf_traffic::Duration for_duration = std::chrono::seconds(30));

    rmf_traffic::PlanId current_plan_id() const;

    class Stubbornness
    {
    public:
      void release();

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

    Stubbornness be_stubborn();

    enum class Decision
    {
      Undefined = 0,
      Clear = 1,
      Crowded = 2
    };

    using Decide = std::function<void(Decision)>;

    using Watchdog = std::function<void(const std::string&, Decide)>;

    void set_lift_entry_watchdog(
      Watchdog watchdog,
      rmf_traffic::Duration wait_duration = std::chrono::seconds(10));

  private:
    friend Implementation;
    Implementation* _pimpl;
  };

  Unstable& unstable();
  const Unstable& unstable() const;

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

using RobotUpdateHandlePtr = std::shared_ptr<RobotUpdateHandle>;
using ConstRobotUpdateHandlePtr = std::shared_ptr<const RobotUpdateHandle>;

} // namespace agv
} // namespace rmf_fleet_adapter

#endif // RMF_FLEET_ADAPTER__AGV__ROBOTUPDATEHANDLE_HPP