Class EasyFullControl::FleetConfiguration
Defined in File EasyFullControl.hpp
Nested Relationships
This class is a nested type of Class EasyFullControl.
Class Documentation
-
class FleetConfiguration
The Configuration class contains parameters necessary to initialize an EasyFullControl fleet instance and add fleets to the adapter.
Public Functions
Constructor
- Parameters:
fleet_name – [in] The name of the fleet that is being added.
transformations_to_robot_coordinates – [in] A dictionary of transformations from RMF canonical coordinates to the the coordinate system used by the robot. Each map should be assigned its own transformation. If this is not nullptr, then a warning will be logged whenever the dictionary is missing a transform for a map, and the canonical RMF coordinates will be used.
traits – [in] Specify the approximate traits of the vehicles in this fleet.
navigation_graph – [in] Specify the navigation graph used by the vehicles in this fleet.
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.
task_categories – [in] Provide callbacks for considering tasks belonging to each category.
action_categories – [in] List of actions that this fleet can perform. Each item represents a category in the PerformAction description.
finishing_request – [in] A factory for a request that should be performed by each robot in this fleet at the end of its assignments.
skip_rotation_commands – [in] If true, navigation requests which would only have the robot rotate in place will not be sent. Instead, navigation requests will always have the final orientation for the destination.
server_uri – [in] The URI for the websocket server that receives updates on tasks and states. If nullopt, data will not be published.
max_delay – [in] Specify the default value for how high the delay of the current itinerary can become before it gets interrupted and replanned.
update_interval – [in] The duration between positional state updates that are sent to the fleet adapter.
default_responsive_wait – [in] Should the robots in this fleet have responsive wait enabled (true) or disabled (false) by default?
default_max_merge_waypoint_distance – [in] The maximum merge distance between a robot position and a waypoint.
default_max_merge_lane_distance – [in] The maximum merge distance between a robot position and a lane.
default_min_lane_length – [in] The minimum length that a lane should have.
-
const std::string &fleet_name() const
Get the fleet name.
-
void set_fleet_name(std::string value)
Set the fleet name.
-
const std::optional<std::unordered_map<std::string, Transformation>> &transformations_to_robot_coordinates() const
Get the transformations into robot coordinates for this fleet.
-
void add_robot_coordinate_transformation(std::string map, Transformation transformation)
Set the transformation into robot coordinates for a map. This will replace any transformation previously set for the map. If the transformation dictionary was previously nullopt, this will initialize it with an empty value before inserting this transformation.
-
const std::unordered_map<std::string, RobotConfiguration> &known_robot_configurations() const
Get a dictionary of known robot configurations. The key is the name of the robot belonging to this fleet. These configurations are usually parsed from a fleet configuration file.
-
std::vector<std::string> known_robots() const
Get the names of all robots with known robot configurations.
-
void add_known_robot_configuration(std::string robot_name, RobotConfiguration configuration)
Provide a known configuration for a named robot.
- Parameters:
robot_name – [in] The unique name of the robot.
configuration – [in] The configuration for the robot.
-
std::optional<RobotConfiguration> get_known_robot_configuration(const std::string &robot_name) const
Get a known configuration for a robot based on its name.
-
const std::shared_ptr<const VehicleTraits> &vehicle_traits() const
Get the fleet vehicle traits.
Set the vehicle traits.
-
const std::shared_ptr<const Graph> &graph() const
Get the fleet navigation graph.
Set the fleet navigation graph.
-
rmf_battery::agv::ConstBatterySystemPtr battery_system() const
Get the battery system.
-
void set_battery_system(rmf_battery::agv::ConstBatterySystemPtr value)
Set the battery system.
-
rmf_battery::ConstMotionPowerSinkPtr motion_sink() const
Get the motion sink.
-
void set_motion_sink(rmf_battery::ConstMotionPowerSinkPtr value)
Set the motion sink.
-
rmf_battery::ConstDevicePowerSinkPtr ambient_sink() const
Get the ambient sink.
-
void set_ambient_sink(rmf_battery::ConstDevicePowerSinkPtr value)
Set the ambient sink.
-
rmf_battery::ConstDevicePowerSinkPtr tool_sink() const
Get the tool sink.
-
void set_tool_sink(rmf_battery::ConstDevicePowerSinkPtr value)
Set the tool sink.
-
double recharge_threshold() const
Get the recharge threshold.
-
void set_recharge_threshold(double value)
Set the recharge threshold.
-
double recharge_soc() const
Get the recharge state of charge. If the robot’s state of charge dips below this value then its next task will be to recharge.
-
void set_recharge_soc(double value)
Set the recharge state of charge.
-
bool account_for_battery_drain() const
Get whether or not to account for battery drain during task planning.
-
void set_account_for_battery_drain(bool value)
Set whether or not to account for battery drain during task planning.
-
const std::unordered_map<std::string, ConsiderRequest> &task_consideration() const
Get the task categories.
-
std::unordered_map<std::string, ConsiderRequest> &task_consideration()
Mutable access to the task consideration map.
-
const std::unordered_map<std::string, ConsiderRequest> &action_consideration() const
Get the action categories.
-
std::unordered_map<std::string, ConsiderRequest> &action_consideration()
Mutable access to the action consideration map.
-
rmf_task::ConstRequestFactoryPtr finishing_request() const
Get the finishing request.
-
void set_finishing_request(rmf_task::ConstRequestFactoryPtr value)
Set the finishing request.
-
bool skip_rotation_commands() const
Check whether rotation commands will be skipped.
-
void set_skip_rotation_commands(bool value)
Set whether rotation commands will be skipped.
-
std::optional<std::string> server_uri() const
Get the server uri.
-
void set_server_uri(std::optional<std::string> value)
Set the server uri.
-
rmf_traffic::Duration max_delay() const
Get the max delay.
-
void set_max_delay(rmf_traffic::Duration value)
Set the max delay.
-
rmf_traffic::Duration update_interval() const
Get the update interval.
-
void set_update_interval(rmf_traffic::Duration value)
Set the update interval.
-
bool default_responsive_wait() const
Should robots in this fleet have responsive wait enabled by default?
-
void set_default_responsive_wait(bool enable)
Set whether robots in this fleet should have responsive wait enabled by default.
-
double default_max_merge_waypoint_distance() const
Get the maximum merge distance between a robot position and a waypoint.
-
void set_default_max_merge_waypoint_distance(double distance)
Set the maximum merge distance between a robot position and a waypoint.
-
double default_max_merge_lane_distance() const
Get the maximum merge distance between a robot position and a lane.
-
void set_default_max_merge_lane_distance(double distance)
Set the maximum merge distance between a robot position and a lane.
-
double default_min_lane_length() const
Get the minimum lane length allowed.
-
void set_default_min_lane_length(double distance)
Set the minimum lane length.
-
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
-
std::unordered_map<std::string, std::string> &change_lift_emergency_levels()
Get mutable access to the level that each specified lift will go to during a fire emergency.
See also
-
const std::unordered_map<std::string, std::string> &lift_emergency_levels() const
Get the level that each specified lift will go to during a fire emergency.
See also
Public Static Functions
-
static std::optional<FleetConfiguration> from_config_files(const std::string &config_file, const std::string &nav_graph_path, std::optional<std::string> server_uri = std::nullopt)
Create a FleetConfiguration object using a set of configuration parameters imported from YAML files that follow the defined schema. This is an alternative to constructing the FleetConfiguration using the RMF objects if users do not require specific tool systems for their fleets. The FleetConfiguration object will be instantiated with instances of SimpleMotionPowerSink and SimpleDevicePowerSink.
- Parameters:
config_file – [in] The path to a configuration YAML file containing data about the fleet’s vehicle traits and task capabilities. This file needs to follow the pre-defined config.yaml structure to successfully load the parameters into the FleetConfiguration object.
nav_graph_path – [in] The path to a navigation path file that includes map information necessary to create a rmf_traffic::agv::Graph object
server_uri – [in] The URI for the websocket server that receives updates on tasks and states. If nullopt, data will not be published.
- Returns:
A FleetConfiguration object with the essential config parameters loaded.