Class TaskPlanner

Nested Relationships

Nested Types

Class Documentation

class TaskPlanner

Public Types

enum class TaskPlannerError

Values:

enumerator low_battery

None of the agents in the initial states have sufficient initial charge to even head back to their charging stations. Manual intervention is needed to recharge one or more agents.

enumerator limited_capacity

None of the agents in the initial states have sufficient battery capacity to accommodate one or more requests. This may be remedied by increasing the battery capacity or by lowering the threshold_soc in the state configs of the agents or by modifying the original request.

using Assignments = std::vector<std::vector<Assignment>>

Container for assignments for each agent.

using Result = std::variant<Assignments, TaskPlannerError>

Public Functions

TaskPlanner(Configuration configuration, Options default_options)

Constructor

Parameters:
  • configuration[in] The configuration for the planner

  • default_options[in] Default options for the task planner to use when solving for assignments. These options can be overriden each time a plan is requested.

TaskPlanner(const std::string &planner_id, Configuration configuration, Options default_options)

Constructor

Parameters:
  • planner_id[in] Identifier of this task planner, to be used for booking automated requests.

  • configuration[in] The configuration for the planner.

  • default_options[in] Default options for the task planner to use when solving for assignments. These options can be overriden each time a plan is requested.

const Configuration &configuration() const

Get a const reference to configuration of this task planner.

const Options &default_options() const

Get a const reference to the default planning options.

Options &default_options()

Get a mutable reference to the default planning options.

Result plan(rmf_traffic::Time time_now, std::vector<State> agents, std::vector<ConstRequestPtr> requests)

Generate assignments for requests among available agents. The default Options of this TaskPlanner instance will be used.

Parameters:
  • time_now[in] The current time when this plan is requested

  • agents[in] The initial states of the agents/AGVs that can undertake the requests

  • requests[in] The set of requests that need to be assigned among the agents/AGVs

Result plan(rmf_traffic::Time time_now, std::vector<State> agents, std::vector<ConstRequestPtr> requests, Options options)

Generate assignments for requests among available agents. Override the default parameters

Parameters:
  • time_now[in] The current time when this plan is requested

  • agents[in] The initial states of the agents/AGVs that can undertake the requests

  • requests[in] The set of requests that need to be assigned among the agents/AGVs

  • options[in] The options to use for this plan. This overrides the default Options of the TaskPlanner instance

double compute_cost(const Assignments &assignments) const

Compute the cost of a set of assignments.

class Assignment

Public Functions

Assignment(rmf_task::ConstRequestPtr request, State finish_state, rmf_traffic::Time deployment_time)

Constructor

Parameters:
  • request[in] The task request for this assignment

  • state[in] The state of the agent at the end of the assigned task

  • earliest_start_time[in] The earliest time the agent will begin exececuting this task

const rmf_task::ConstRequestPtr &request() const
const State &finish_state() const
const rmf_traffic::Time deployment_time() const
class Configuration

The Configuration class contains planning parameters that are immutable for each TaskPlanner instance and should not change in between plans.

Public Functions

Configuration(Parameters parameters, Constraints constraints, ConstCostCalculatorPtr cost_calculator)

Constructor

Parameters:
  • parameters[in] The parameters that describe the agents

  • constraints[in] The constraints that apply to the agents

  • cost_calculator[in] An object that tells the planner how to calculate cost

const Parameters &parameters() const

Get the parameters that describe the agents.

Configuration &parameters(Parameters parameters)

Set the parameters that describe the agents.

const Constraints &constraints() const

Get the constraints that are applicable to the agents.

Configuration &constraints(Constraints constraints)

Set the constraints that are applicable to the agents.

const ConstCostCalculatorPtr &cost_calculator() const

Get the CostCalculator.

Configuration &cost_calculator(ConstCostCalculatorPtr cost_calculator)

Set the CostCalculator. If a nullptr is passed, the BinaryPriorityCostCalculator is used by the planner.

class Options

The Options class contains planning parameters that can change between each planning attempt.

Public Functions

Options(bool greedy, std::function<bool()> interrupter = nullptr, ConstRequestFactoryPtr finishing_request = nullptr)

Constructor

Parameters:
  • greedy[in] If true, a greedy approach will be used to solve for the task assignments. Optimality is not guaranteed but the solution time may be faster. If false, an A* based approach will be used within the planner which guarantees optimality but may take longer to solve.

  • interrupter[in] A function that can determine whether the planning should be interrupted.

  • finishing_request[in] A request factory that generates a tailored task for each agent/AGV to perform at the end of their assignments

Options &greedy(bool value)

Set whether a greedy approach should be used.

bool greedy() const

Get whether a greedy approach will be used.

Options &interrupter(std::function<bool()> interrupter)

Set an interrupter callback that will indicate to the planner if it should stop trying to plan

const std::function<bool()> &interrupter() const

Get the interrupter that will be used in this Options.

Options &finishing_request(ConstRequestFactoryPtr finishing_request)

Set the request factory that will generate a finishing task.

ConstRequestFactoryPtr finishing_request() const

Get the request factory that will generate a finishing task.