Class FleetUpdateHandle
Defined in File FleetUpdateHandle.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public std::enable_shared_from_this< FleetUpdateHandle >
Class Documentation
-
class FleetUpdateHandle : public std::enable_shared_from_this<FleetUpdateHandle>
Public Types
-
using ConsiderRequest = std::function<void(const nlohmann::json &description, Confirmation &confirm)>
Signature for a callback that decides whether to accept a specific category of task request.
- Param description:
[in] A description of the task that is being considered
- Param confirm:
[in] Use this object to decide if you want to accept the task
-
using AcceptTaskRequest = std::function<bool(const rmf_task_msgs::msg::TaskProfile &profile)>
A callback function that evaluates whether a fleet will accept a task request
- Param request:
[in] Information about the task request that is being considered.
- Return:
true to indicate that this fleet should accept the request, false to reject the request.
-
using AcceptDeliveryRequest = std::function<bool(const rmf_task_msgs::msg::Delivery &request)>
A callback function that evaluates whether a fleet will accept a delivery request.
- Param request:
[in] Information about the delivery request that is being considered.
- Return:
true to indicate that this fleet should accept the request, false to reject the request.
Public Functions
-
const std::string &fleet_name() const
Get the name of the fleet that his handle is managing.
Add a robot to this fleet adapter.
- Parameters:
command – [in] A reference to a command handle for this robot.
name – [in] The name of this robot.
profile – [in] The profile of this robot. This profile should account for the largest possible payload that the robot might carry.
start – [in] The initial location of the robot, expressed as a Plan::StartSet. Multiple Start objects might be needed if the robot is not starting precisely on a waypoint. The function rmf_traffic::agv::compute_plan_starts() may help with this.
handle_cb – [in] This callback function will get triggered when the RobotUpdateHandle is ready to be used by the Fleet API side of the Adapter. Setting up a new robot requires communication with the Schedule Node, so there may be a delay before the robot is ready to be used.
- Returns:
a handle to give the adapter updates about the robot.
-
FleetUpdateHandle &consider_delivery_requests(ConsiderRequest consider_pickup, ConsiderRequest consider_dropoff)
Allow this fleet adapter to consider delivery requests.
Pass in nullptrs to disable delivery requests.
By default, delivery requests are not accepted until you provide these callbacks.
The FleetUpdateHandle will ensure that the requests are feasible for the robots before triggering these callbacks.
- Parameters:
consider_pickup – [in] Decide whether to accept a pickup request. The description will satisfy the event_description_PickUp.json schema of rmf_fleet_adapter.
consider_dropoff – [in] Decide whether to accept a dropoff request. The description will satisfy the event_description_DropOff.json schema of rmf_fleet_adapter.
-
FleetUpdateHandle &consider_cleaning_requests(ConsiderRequest consider)
Allow this fleet adapter to consider cleaning requests.
Pass in a nullptr to disable cleaning requests.
By default, cleaning requests are not accepted until you provide this callback.
- Parameters:
consider – [in] Decide whether to accept a cleaning request. The description will satisfy the event_description_Clean.json schema of rmf_fleet_adapter. The FleetUpdateHandle will ensure that the request is feasible for the robots before triggering this callback.
-
FleetUpdateHandle &consider_patrol_requests(ConsiderRequest consider)
Allow this fleet adapter to consider patrol requests.
Pass in a nullptr to disable patrol requests.
By default, patrol requests are always accepted.
- Parameters:
consider – [in] Decide whether to accept a patrol request. The description will satisfy the task_description_Patrol.json schema of rmf_fleet_adapter. The FleetUpdateHandle will ensure that the request is feasible for the robots before triggering this callback.
-
FleetUpdateHandle &consider_composed_requests(ConsiderRequest consider)
Allow this fleet adapter to consider composed requests.
Pass in a nullptr to disable composed requests.
By default, composed requests are always accepted, as long as the events that they are composed of are accepted.
- Parameters:
consider – [in] Decide whether to accept a composed request. The description will satisfy the task_description_Compose.json schema of rmf_fleet_adapter. The FleetUpdateHandle will ensure that the request is feasible for the robots before triggering this callback.
-
FleetUpdateHandle &add_performable_action(const std::string &category, ConsiderRequest consider)
Allow this fleet adapter to execute a PerformAction activity of specified category which may be present in sequence event.
- Parameters:
category – [in] A string that categorizes the action. This value should be used when filling out the category field in event_description_PerformAction.json schema.
consider – [in] Decide whether to accept the action based on the description field in event_description_PerformAction.json schema.
-
void close_lanes(std::vector<std::size_t> lane_indices)
Specify a set of lanes that should be closed.
-
void open_lanes(std::vector<std::size_t> lane_indices)
Specify a set of lanes that should be open.
-
void set_lift_emergency_level(std::string lift_name, std::string emergency_level_name)
During a fire emergency, real-life lifts might be required to move to a specific level and refuse to stop or go to any other level. This function lets you provide this information to the fleet adapter so that it can produce reasonable emergency pullover plans for robots that happen to be inside of a lift when the fire alarm goes off.
Internally, this will close all lanes that go into the specified lift and close all lanes exiting this lift (except on the designated level) when a fire emergency begins. Lifts that were not specified in a call to this function will not behave any differently during a fire emergency.
- Parameters:
lift_name – [in] The name of the lift whose behavior is being specified
emergency_level_name – [in] The level that lift will go to when a fire emergency is happening
-
void limit_lane_speeds(std::vector<SpeedLimitRequest> requests)
Impose speed limits on specified lanes.
-
void remove_speed_limits(std::vector<std::size_t> requests)
Remove speed limits from specified lanes.
-
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)
Set the parameters required for task planning. Without calling this function, this fleet will not bid for and accept tasks.
- Parameters:
battery_system – [in] Specify the battery system used by the vehicles in this fleet.
motion_sink – [in] Specify the motion sink that describes the vehicles in this fleet.
ambient_sink – [in] Specify the device sink for ambient sensors used by the vehicles in this fleet.
tool_sink – [in] Specify the device sink for special tools used by the vehicles in this fleet.
recharge_threshold – [in] The threshold for state of charge below which robots in this fleet will cease to operate and require recharging. A value between 0.0 and 1.0 should be specified.
recharge_soc – [in] The state of charge to which robots in this fleet should be charged up to by automatic recharging tasks. A value between 0.0 and 1.0 should be specified.
account_for_battery_drain – [in] Specify whether battery drain is to be considered while allocating tasks. If false, battery drain will not be considered when planning for tasks. As a consequence, charging tasks will not be automatically assigned to vehicles in this fleet when battery levels fall below the recharge_threshold.
finishing_request – [in] A factory for a request that should be performed by each robot in this fleet at the end of its assignments.
- Returns:
true if task planner parameters were successfully updated.
-
FleetUpdateHandle &accept_task_requests(AcceptTaskRequest check)
Provide a callback that indicates whether this fleet will accept a BidNotice request. By default all requests will be rejected.
Note
The callback function that you give should ideally be non-blocking and return quickly. It’s meant to check whether this fleet’s vehicles are compatible with the requested payload, pickup, and dropoff behavior settings. The path planning feasibility will be taken care of by the adapter internally.
-
FleetUpdateHandle &accept_delivery_requests(AcceptDeliveryRequest check)
Provide a callback that indicates whether this fleet will accept a delivery request. By default all delivery requests will be rejected.
Note
The callback function that you give should ideally be non-blocking and return quickly. It’s meant to check whether this fleet’s vehicles are compatible with the requested payload, pickup, and dropoff behavior settings. The path planning feasibility will be taken care of by the adapter internally.
-
FleetUpdateHandle &default_maximum_delay(std::optional<rmf_traffic::Duration> value)
Specify the default value for how high the delay of the current itinerary can become before it gets interrupted and replanned. A nullopt value will allow for an arbitrarily long delay to build up without being interrupted.
-
std::optional<rmf_traffic::Duration> default_maximum_delay() const
Get the default value for the maximum acceptable delay.
-
FleetUpdateHandle &fleet_state_publish_period(std::optional<rmf_traffic::Duration> value)
The behavior is identical to fleet_state_topic_publish_period.
-
FleetUpdateHandle &fleet_state_topic_publish_period(std::optional<rmf_traffic::Duration> value)
Specify a period for how often the fleet state message is published for this fleet. Passing in std::nullopt will disable the fleet state message publishing. The default value is 1s.
-
FleetUpdateHandle &fleet_state_update_period(std::optional<rmf_traffic::Duration> value)
Specify a period for how often the fleet state is updated in the database and to the API server. This is separate from publishing the fleet state over the ROS2 fleet state topic. Passing in std::nullopt will disable the updating, but this is not recommended unless you intend to provide the API server with the fleet states through some other means.
The default value is 1s.
-
FleetUpdateHandle &set_update_listener(std::function<void(const nlohmann::json&)> listener)
Set a callback for listening to update messages (e.g. fleet states and task updates). This will not receive any update messages that happened before the listener was set.
-
std::shared_ptr<rclcpp::Node> node()
Get the rclcpp::Node that this fleet update handle will be using for communication.
-
FleetUpdateHandle(FleetUpdateHandle&&) = delete
-
FleetUpdateHandle &operator=(FleetUpdateHandle&&) = delete
-
class Confirmation
Confirmation is a class used by the task acceptance callbacks to decide if a task description should be accepted.
Public Functions
-
Confirmation()
Constructor.
-
Confirmation &accept()
Call this function to decide that you want to accept the task request. If this function is never called, it will be assumed that the task is rejected.
-
bool is_accepted() const
Check whether.
-
Confirmation &errors(std::vector<std::string> error_messages)
Call this function to bring attention to errors related to the task request. Each call to this function will overwrite any past calls, so it is recommended to only call it once.
-
Confirmation &add_errors(std::vector<std::string> error_messages)
Call this function to add errors instead of overwriting the ones that were already there.
-
const std::vector<std::string> &errors() const
Check the errors that have been given to this confirmation.
-
Confirmation()
-
class SpeedLimitRequest
A class used to describe speed limit imposed on lanes.
Public Functions
-
SpeedLimitRequest(std::size_t lane_index, double speed_limit)
Constructor
- Parameters:
lane_index – [in] The index of the lane to impose a speed limit upon.
speed_limit – [in] The speed limit to be imposed for this lane.
-
std::size_t lane_index() const
Get the lane_index.
-
double speed_limit() const
Get the speed_limit.
-
SpeedLimitRequest(std::size_t lane_index, double speed_limit)
-
using ConsiderRequest = std::function<void(const nlohmann::json &description, Confirmation &confirm)>