Class EasyFullControl

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public std::enable_shared_from_this< EasyFullControl >

Class Documentation

class EasyFullControl : public std::enable_shared_from_this<EasyFullControl>

An easy to initialize full_control fleet adapter. By default the adapter will be configured to accept all tasks. To disable specific tasks, call the respective consider_*_requests() method on the FleetUpdateHandle that can be accessed within this adapter.

Public Types

using Graph = rmf_traffic::agv::Graph
using VehicleTraits = rmf_traffic::agv::VehicleTraits
using ActionExecutor = RobotUpdateHandle::ActionExecutor
using ActivityIdentifier = RobotUpdateHandle::ActivityIdentifier
using ActivityIdentifierPtr = RobotUpdateHandle::ActivityIdentifierPtr
using ConstActivityIdentifierPtr = RobotUpdateHandle::ConstActivityIdentifierPtr
using Stubbornness = RobotUpdateHandle::Unstable::Stubbornness
using ConsiderRequest = FleetUpdateHandle::ConsiderRequest
using NavigationRequest = std::function<void(Destination destination, CommandExecution execution)>

Signature for a function that handles navigation requests. The request will specify a destination for the robot to go to.

Param destination:

[in] Where the robot should move to. Includings (x, y) coordinates, a target yaw, a map name, and may include a graph index when one is available.

Param execution:

[in] The command execution progress updater. Use this to keep the fleet adapter updated on the progress of the command.

using StopRequest = std::function<void(ConstActivityIdentifierPtr)>

Signature for a function to handle stop requests.

using LocalizationRequest = std::function<void(Destination location_estimate, CommandExecution execution)>

Signature for a function that handles localization requests. The request will specify an approximate location for the robot.

Param location_estimate:

[in] An estimate for where the robot is currently located.

Param execution:

[in] The command execution progress updater. Use this to keep the fleet adapter updated on the progress of localizing.

Public Functions

std::shared_ptr<EasyRobotUpdateHandle> add_robot(std::string name, RobotState initial_state, RobotConfiguration configuration, RobotCallbacks callbacks)

Add a robot to the fleet once it is available.

Parameters:
  • name[in] Name of the robot. This must be unique per fleet.

  • initial_state[in] The initial state of the robot when it is added to the fleet.

  • configuration[in] The configuration of the robot.

  • callbacks[in] The callbacks that will be used to issue commands for the robot.

Returns:

an easy robot update handle on success. A nullptr if an error occurred.

std::shared_ptr<FleetUpdateHandle> more()

Get the FleetUpdateHandle that this adapter will be using. This may be used to perform more specialized customizations using the base FleetUpdateHandle API.

std::shared_ptr<const FleetUpdateHandle> more() const

Immutable reference to the base FleetUpdateHandle API.

class CommandExecution

Used by system integrators to give feedback on the progress of executing a navigation or docking command.

Public Functions

void finished()

Trigger this when the command is successfully finished. No other function in this CommandExecution instance will be usable after this.

bool okay() const

Returns false if the command has been stopped.

Stubbornness override_schedule(std::string map, std::vector<Eigen::Vector3d> path, rmf_traffic::Duration hold = rmf_traffic::Duration(0))

Use this to override the traffic schedule for the agent while it performs this command.

If the given trajectory results in a traffic conflict then a negotiation will be triggered. Hold onto the Stubbornness returned by this function to ask other agents to plan around your trajectory, otherwise the negotiation may result in a replan for this agent and a new command will be issued.

Note

Using this will function always trigger a replan once the agent finishes the command.

Warning

Too many overridden/stubborn agents can cause a deadlock. It’s recommended to use this API sparingly and only over short distances or small deviations.

Parameters:
  • map[in] Name of the map where the trajectory will take place

  • path[in] The path of the agent

  • hold[in] How long the agent will wait at the end of the path

Returns:

a Stubbornness handle that tells the fleet adapter to not let the overridden path be negotiated. The returned handle will stop having an effect after this command execution is finished.

ConstActivityIdentifierPtr identifier() const

Activity handle for this command. Pass this into EasyRobotUpdateHandle::update_position while executing this command.

class Destination

Public Functions

const std::string &map() const

The name of the map where the destination is located.

Eigen::Vector3d position() const

The (x, y, yaw) position of the destination.

Eigen::Vector2d xy() const

The (x, y) position of the destination.

double yaw() const

The intended orientation of the robot at the destination, represented in radians.

std::optional<std::size_t> graph_index() const

If the destination has an index in the navigation graph, you can get it from this field.

std::string name() const

The name of this destination, if it has one. Nameless destinations will give an empty string.

std::optional<double> speed_limit() const

If there is a speed limit that should be respected while approaching the destination, this will indicate it.

std::optional<std::string> dock() const

If the destination should be reached by performing a dock maneuver, this will contain the name of the dock.

rmf_traffic::agv::Graph::LiftPropertiesPtr inside_lift() const

Get whether the destination is inside of a lift, and if so get the properties of the lift.

class EasyRobotUpdateHandle

Handle used to update information about one robot.

Public Functions

void update(RobotState state, ConstActivityIdentifierPtr current_activity)

Recommended function for updating information about a robot in an EasyFullControl fleet.

Parameters:
  • state[in] The current state of the robot

  • current_action[in] The action that the robot is currently executing

double max_merge_waypoint_distance() const

Get the maximum allowed merge waypoint distance for this robot.

void set_max_merge_waypoint_distance(double distance)

Modify the maximum allowed merge distance between the robot and a waypoint.

Parameters:

max_merge_waypoint_distance[in] The maximum merge waypoint distance for this robot.

double max_merge_lane_distance() const

Get the maximum allowed merge lane distance for this robot.

void set_max_merge_lane_distance(double distance)

Modify the maximum allowed merge distance between the robot and a lane.

Parameters:

max_merge_lane_distance[in] The maximum merge lane distance for this robot.

double min_lane_length() const

Get the minimum lane length for this robot.

void set_min_lane_length(double length)

Modify the minimum lane length for this robot.

Parameters:

min_lane_length[in] The minimum length of a lane.

std::shared_ptr<RobotUpdateHandle> more()

Get more options for updating the robot’s state.

std::shared_ptr<const RobotUpdateHandle> more() const

Immutable reference to the base robot update API.

class FleetConfiguration

The Configuration class contains parameters necessary to initialize an EasyFullControl fleet instance and add fleets to the adapter.

Public Functions

FleetConfiguration(const std::string &fleet_name, std::optional<std::unordered_map<std::string, Transformation>> transformations_to_robot_coordinates, std::unordered_map<std::string, RobotConfiguration> known_robot_configurations, std::shared_ptr<const rmf_traffic::agv::VehicleTraits> traits, std::shared_ptr<const rmf_traffic::agv::Graph> graph, 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, std::unordered_map<std::string, ConsiderRequest> task_consideration, std::unordered_map<std::string, ConsiderRequest> action_consideration, rmf_task::ConstRequestFactoryPtr finishing_request = nullptr, bool skip_rotation_commands = true, std::optional<std::string> server_uri = std::nullopt, rmf_traffic::Duration max_delay = rmf_traffic::time::from_seconds(10.0), rmf_traffic::Duration update_interval = rmf_traffic::time::from_seconds(0.5), bool default_responsive_wait = false, double default_max_merge_waypoint_distance = 1e-3, double default_max_merge_lane_distance = 0.3, double min_lane_length = 1e-8)

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.

  • retreat_to_charger_interval[in] Specify whether to allow automatic retreat to charger if the robot’s battery is estimated to fall below its recharge_threshold before it is able to complete its current task. Provide a duration between checks in seconds. If nullopt, retreat to charger would be disabled.

  • 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.

void set_vehicle_traits(std::shared_ptr<const VehicleTraits> value)

Set the vehicle traits.

const std::shared_ptr<const Graph> &graph() const

Get the fleet navigation graph.

void set_graph(std::shared_ptr<const Graph> value)

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.

std::optional<rmf_traffic::Duration> retreat_to_charger_interval() const

Get the duration between retreat to charger checks.

void set_retreat_to_charger_interval(std::optional<rmf_traffic::Duration> value)

Set the duration between retreat to charger checks. Passing in a nullopt will turn off these checks entirely.

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.

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.

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.

class RobotCallbacks

Public Functions

RobotCallbacks(NavigationRequest navigate, StopRequest stop, ActionExecutor action_executor)

Constructor

Parameters:
  • navigate[in] A function that can be used to request the robot to navigate to a location. The function returns a handle which can be used to track the progress of the navigation.

  • stop[in] A function to stop the robot.

  • action_executor[in] The ActionExecutor callback to request the robot to perform an action.

NavigationRequest navigate() const

Get the callback for navigation.

StopRequest stop() const

Get the callback for stopping.

ActionExecutor action_executor() const

Get the action executor.

RobotCallbacks &with_localization(LocalizationRequest localization)

Give the robot a localization callback. Unlike the callbacks used by the constructor, this callback is optional.

LocalizationRequest localize() const

Get the callback for localizing if available.

class RobotConfiguration

The configuration of a robot. These are parameters that typically do not change over time.

Public Functions

RobotConfiguration(std::vector<std::string> compatible_chargers, std::optional<bool> responsive_wait = std::nullopt, std::optional<double> max_merge_waypoint_distance = 1e-3, std::optional<double> max_merge_lane_distance = 0.3, std::optional<double> min_lane_length = 1e-8)

Constructor

Warning

This must contain a single string value until a later release of RMF. We are using a vector for forward API compatibility. For now, make sure each robot has only one unique compatible charger to avoid charging conflicts.

Parameters:
  • compatible_chargers[in] List of chargers that this robot is compatible with

  • responsive_wait[in] Should this robot use the responsive wait behavior? true / false / fleet default.

const std::vector<std::string> &compatible_chargers() const

List of chargers that this robot is compatible with.

void set_compatible_chargers(std::vector<std::string> chargers)

Set the list of chargers compatible with this robot.

std::optional<bool> responsive_wait() const

Should this robot use the responsive wait behavior? Responsive wait means that when the robot is idle on a point, it will report to the traffic schedule that it is waiting on that point, and it will negotiate with other robots to let them pass while ultimately remaining on the point.

If std::nullopt is used, then the fleet-wide responsive wait behavior will be used.

void set_responsive_wait(std::optional<bool> enable)

Toggle responsive wait on (true), off (false), or use fleet default (std::nullopt).

std::optional<double> max_merge_waypoint_distance() const

Get the maximum merge distance between a robot and a waypoint. This refers to the maximum distance allowed to consider a robot to be on a particular waypoint.

If std::nullopt is used, then the fleet-wide default merge waypoint distance will be used.

void set_max_merge_waypoint_distance(std::optional<double> distance)

Set the maximum merge distance between a robot and a waypoint.

std::optional<double> max_merge_lane_distance() const

Get the maximum merge distance between a robot and a lane. This refers to the maximum distance allowed to consider a robot to be on a particular lane.

If std::nullopt is used, then the fleet-wide default merge lane distance will be used.

void set_max_merge_lane_distance(std::optional<double> distance)

Set the maximum merge distance between a robot and a lane.

std::optional<double> min_lane_length() const

Get the minimum lane length.

If std::nullopt is used, then the fleet-wide default minimum lane length will be used.

void set_min_lane_length(std::optional<double> distance)

Set the minimum lane length.

class RobotState

The current state of a robot, passed into EasyRobotUpdateHandle::update.

Public Functions

RobotState(std::string map_name, Eigen::Vector3d position, double battery_soc)

Constructor

Parameters:
  • map_name[in] The name of the map the robot is currently on

  • position[in] The current position of the robot

  • battery_soc[in] the current battery level of the robot, specified by its state of charge as a fraction of its total charge capacity, i.e. a value from 0.0 to 1.0.

const std::string &map() const

Current map the robot is on.

void set_map(std::string value)

Set the current map the robot is on.

Eigen::Vector3d position() const

Current position of the robot.

void set_position(Eigen::Vector3d value)

Set the current position of the robot.

double battery_state_of_charge() const

Current state of charge of the battery, as a fraction from 0.0 to 1.0.

void set_battery_state_of_charge(double value)

Set the state of charge of the battery, as a fraction from 0.0 to 1.0.