Program Listing for File FleetUpdateHandle.hpp
↰ Return to documentation for file (include/rmf_fleet_adapter/agv/FleetUpdateHandle.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__FLEETUPDATEHANDLE_HPP
#define RMF_FLEET_ADAPTER__AGV__FLEETUPDATEHANDLE_HPP
#include <rmf_fleet_adapter/agv/RobotUpdateHandle.hpp>
#include <rmf_fleet_adapter/agv/RobotCommandHandle.hpp>
#include <rmf_task_msgs/msg/delivery.hpp>
#include <rmf_task_msgs/msg/task_profile.hpp>
#include <rmf_battery/agv/BatterySystem.hpp>
#include <rmf_battery/DevicePowerSink.hpp>
#include <rmf_battery/MotionPowerSink.hpp>
#include <rmf_task/RequestFactory.hpp>
#include <nlohmann/json.hpp>
#include <rmf_task/Activator.hpp>
#include <rmf_task_sequence/Phase.hpp>
#include <rmf_task_sequence/Event.hpp>
#include <rclcpp/node.hpp>
namespace rmf_fleet_adapter {
namespace agv {
//==============================================================================
class FleetUpdateHandle : public std::enable_shared_from_this<FleetUpdateHandle>
{
public:
const std::string& fleet_name() const;
void add_robot(
std::shared_ptr<RobotCommandHandle> command,
const std::string& name,
const rmf_traffic::Profile& profile,
rmf_traffic::agv::Plan::StartSet start,
std::function<void(std::shared_ptr<RobotUpdateHandle> handle)> handle_cb);
class Confirmation
{
public:
Confirmation();
Confirmation& accept();
bool is_accepted() const;
Confirmation& errors(std::vector<std::string> error_messages);
Confirmation& add_errors(std::vector<std::string> error_messages);
const std::vector<std::string>& errors() const;
class Implementation;
private:
rmf_utils::impl_ptr<Implementation> _pimpl;
};
using ConsiderRequest =
std::function<void(
const nlohmann::json& description,
Confirmation& confirm)
>;
FleetUpdateHandle& consider_delivery_requests(
ConsiderRequest consider_pickup,
ConsiderRequest consider_dropoff);
FleetUpdateHandle& consider_cleaning_requests(ConsiderRequest consider);
FleetUpdateHandle& consider_patrol_requests(ConsiderRequest consider);
FleetUpdateHandle& consider_composed_requests(ConsiderRequest consider);
FleetUpdateHandle& add_performable_action(
const std::string& category,
ConsiderRequest consider);
void close_lanes(std::vector<std::size_t> lane_indices);
void open_lanes(std::vector<std::size_t> lane_indices);
void set_lift_emergency_level(
std::string lift_name,
std::string emergency_level_name);
class SpeedLimitRequest
{
public:
SpeedLimitRequest(
std::size_t lane_index,
double speed_limit);
std::size_t lane_index() const;
double speed_limit() const;
class Implementation;
private:
rmf_utils::impl_ptr<Implementation> _pimpl;
};
void limit_lane_speeds(std::vector<SpeedLimitRequest> requests);
void remove_speed_limits(std::vector<std::size_t> requests);
bool set_task_planner_params(
rmf_battery::agv::ConstBatterySystemPtr battery_system,
rmf_battery::ConstMotionPowerSinkPtr motion_sink,
rmf_battery::ConstDevicePowerSinkPtr ambient_sink,
rmf_battery::ConstDevicePowerSinkPtr tool_sink,
double recharge_threshold,
double recharge_soc,
bool account_for_battery_drain,
rmf_task::ConstRequestFactoryPtr finishing_request = nullptr);
using AcceptTaskRequest =
std::function<bool(const rmf_task_msgs::msg::TaskProfile& profile)>;
[[deprecated("Use the consider_..._requests functions instead")]]
FleetUpdateHandle& accept_task_requests(AcceptTaskRequest check);
using AcceptDeliveryRequest =
std::function<bool(const rmf_task_msgs::msg::Delivery& request)>;
[[deprecated("Use consider_delivery_requests() instead")]]
FleetUpdateHandle& accept_delivery_requests(AcceptDeliveryRequest check);
FleetUpdateHandle& default_maximum_delay(
std::optional<rmf_traffic::Duration> value);
std::optional<rmf_traffic::Duration> default_maximum_delay() const;
[[deprecated("Use fleet_state_topic_publish_period instead")]]
FleetUpdateHandle& fleet_state_publish_period(
std::optional<rmf_traffic::Duration> value);
FleetUpdateHandle& fleet_state_topic_publish_period(
std::optional<rmf_traffic::Duration> value);
FleetUpdateHandle& fleet_state_update_period(
std::optional<rmf_traffic::Duration> value);
FleetUpdateHandle& set_update_listener(
std::function<void(const nlohmann::json&)> listener);
std::shared_ptr<rclcpp::Node> node();
std::shared_ptr<const rclcpp::Node> node() const;
// Do not allow moving
FleetUpdateHandle(FleetUpdateHandle&&) = delete;
FleetUpdateHandle& operator=(FleetUpdateHandle&&) = delete;
class Implementation;
private:
FleetUpdateHandle();
rmf_utils::unique_impl_ptr<Implementation> _pimpl;
};
using FleetUpdateHandlePtr = std::shared_ptr<FleetUpdateHandle>;
using ConstFleetUpdateHandlePtr = std::shared_ptr<const FleetUpdateHandle>;
FleetUpdateHandle::ConsiderRequest consider_all();
} // namespace agv
} // namespace rmf_fleet_adapter
#endif // RMF_FLEET_ADAPTER__AGV__FLEETUPDATEHANDLE_HPP