API Reference
Index
CRCBS.AStarCRCBS.AbstractCostModelCRCBS.AbstractLowLevelEnvCRCBS.BenchmarkInterface.MovingAIBenchmarkFileCRCBS.BenchmarkInterface.ProblemLoaderCRCBS.CBSSolverCRCBS.CompositeCostModelCRCBS.ConflictTableCRCBS.ConflictTableHeuristicCRCBS.ConstraintTreeNodeCRCBS.DeadlineCostCRCBS.DiscreteConstraintTableCRCBS.EnvDeadlineCostCRCBS.EnvDistanceHeuristicCRCBS.FeatureExtractorCRCBS.FullCostModelCRCBS.GraphEnvCRCBS.HardConflictTableCRCBS.LowLevelCostModelCRCBS.LowLevelSearchHeuristicCRCBS.LowLevelSolutionCRCBS.MAPFCRCBS.MetaAgentCBS_SolverCRCBS.MetaCostCRCBS.MetaCostModelCRCBS.MetaSolutionCRCBS.MultiDeadlineCostCRCBS.MultiStageEnvDistanceHeuristicCRCBS.MultiStagePerfectHeuristicCRCBS.NullCostCRCBS.NullHeuristicCRCBS.PIBTCacheCRCBS.PIBTPlannerCRCBS.PIBTReservationTableCRCBS.PathCRCBS.PathNodeCRCBS.PerfectHeuristicCRCBS.ReservationTableCRCBS.ResourceReservationCRCBS.SoftConflictTableCRCBS.SoftConflictTableCRCBS.SolverExceptionCRCBS.SolverLoggerCRCBS.SolverWrapperCRCBS.TransformCostModelCRCBS.TravelDistanceCRCBS.TravelTimeCRCBS.BenchmarkInterface.is_same_scenario_and_bucketCRCBS.BenchmarkInterface.parse_map_fileCRCBS.BenchmarkInterface.parse_mapf_scenarioCRCBS.BenchmarkInterface.profile_with_skipping!CRCBS.a_star!CRCBS.a_star_impl!CRCBS.accumulate_costCRCBS.action_space_traitCRCBS.add_conflict!CRCBS.add_constraint!CRCBS.add_constraint!CRCBS.add_fat_path_to_table!CRCBS.add_heuristic_costCRCBS.add_to_path!CRCBS.aggregate_costsCRCBS.aggregate_costs_metaCRCBS.build_envCRCBS.cbs!CRCBS.cbs_branch!CRCBS.cbs_bypass!CRCBS.cbs_update_conflict_table!CRCBS.check_termination_criteriaCRCBS.combine_agents!CRCBS.compute_heuristic_costCRCBS.compute_path_costCRCBS.construct_config_dataframeCRCBS.construct_config_dataframeCRCBS.construct_empty_lookup_tableCRCBS.construct_results_dataframeCRCBS.construct_results_dataframeCRCBS.convert_to_vertex_listsCRCBS.count_conflictsCRCBS.create_reservationsCRCBS.create_reservationsCRCBS.default_solutionCRCBS.deserializeCRCBS.detect_action_conflictCRCBS.detect_action_conflictCRCBS.detect_conflicts!CRCBS.detect_conflicts!CRCBS.detect_conflicts!CRCBS.detect_conflicts!CRCBS.detect_state_conflictCRCBS.detect_state_conflictCRCBS.extend_pathCRCBS.extend_path!CRCBS.extract_featureCRCBS.generate_constraints_from_conflictCRCBS.get_aCRCBS.get_aCRCBS.get_agent_idxsCRCBS.get_conflict_indexCRCBS.get_conflicting_pathsCRCBS.get_conflictsCRCBS.get_constraintsCRCBS.get_cost_modelCRCBS.get_fat_pathCRCBS.get_fat_path_costCRCBS.get_heuristic_costCRCBS.get_infeasible_costCRCBS.get_infeasible_costCRCBS.get_infeasible_solutionCRCBS.get_initial_costCRCBS.get_initial_costCRCBS.get_initial_solutionCRCBS.get_level_set_nodesCRCBS.get_mdd_graphCRCBS.get_next_conflictCRCBS.get_next_stateCRCBS.get_path_costCRCBS.get_path_nodeCRCBS.get_possible_actionsCRCBS.get_sCRCBS.get_sCRCBS.get_spCRCBS.get_spCRCBS.get_transition_costCRCBS.handle_solver_exceptionCRCBS.hard_reset_solver!CRCBS.hard_reset_solver!CRCBS.has_constraintCRCBS.init_dataframeCRCBS.init_dataframeCRCBS.init_mapf_2CRCBS.init_mapf_3CRCBS.init_mapf_4CRCBS.init_mapf_5CRCBS.init_mapf_6CRCBS.init_mapf_7CRCBS.init_mapf_8CRCBS.initialize_child_search_nodeCRCBS.initialize_root_nodeCRCBS.is_availableCRCBS.is_consistentCRCBS.is_goalCRCBS.is_validCRCBS.load_problemCRCBS.low_level_search!CRCBS.num_actionsCRCBS.num_statesCRCBS.partially_set_path!CRCBS.pibt_priority_lawCRCBS.pibt_step!CRCBS.populate_soft_lookup_table!CRCBS.profile_solver!CRCBS.profile_solver!CRCBS.recompute_costCRCBS.reconstruct_path!CRCBS.remove_constraint!CRCBS.reserve!CRCBS.reserved_byCRCBS.reset_solver!CRCBS.reset_solver!CRCBS.reset_undecided!CRCBS.run_profilingCRCBS.run_profilingCRCBS.search_constraintsCRCBS.serializeCRCBS.set_constraint!CRCBS.soft_reset_solver!CRCBS.solve!CRCBS.solve!CRCBS.sorted_actionsCRCBS.state_space_traitCRCBS.states_matchCRCBS.time_to_deadlineCRCBS.trim_path!CRCBS.trim_solution!CRCBS.update_fat_path_conflict_table!CRCBS.violates_constraintsCRCBS.waitCRCBS.write_resultsCRCBS.write_resultsGraphUtils.get_graph
Docs
CRCBS.AbstractCostModel — TypeAbstractCostModel{T}CRCBS.AbstractLowLevelEnv — TypeAbstractLowLevelEnv{S,A,C}Defines a prototype environment for low level search (searching for a path for a single agent).
S is the State type, A is the action type, and C is the cost type. All three must be default constructible (i.e. you can call S(), A() and C() without throwing errors)
In general, a concrete subtype of AbstractLowLevelEnv may include a graph whose edges are traversed by agents.
CRCBS.CompositeCostModel — TypeCompositeCostModel{T}Combines multiple cost models in a specific order (i.e., to use for cascaded tie-breaking).
CRCBS.ConflictTable — TypeA lookup table to store all conflicts that have been detected
CRCBS.ConflictTableHeuristic — TypeConflictTableHeuristic{T<:Union{HardConflictTable,SoftConflictTable}} <: LowLevelSearchHeuristic{Float64}Heuristic model based on conflicts between paths.
CRCBS.ConstraintTreeNode — TypeA node of a constraint tree. Each node has a set of constraints, a candidate solution (set of robot paths), and a cost
CRCBS.DeadlineCost — TypeDeadlineCostIdentical to TravelTime, except for the behavior of add_heuristic_cost.
addheuristiccost: c = max(0.0, t + Δt - deadline)
CRCBS.DiscreteConstraintTable — TypeDiscreteStateTableStores constraints for a discrete state space
CRCBS.EnvDeadlineCost — TypeEnvDeadlineCostDeadlines come from an external environment
CRCBS.FullCostModel — TypeFullCostModel{F,T,M<:AbstractCostModel{T}} <: AbstractCostModel{T}The FullCostModel defines all the behavior required for running CBS-based algorithms.
Elements:
- f::F must be callable, and defines how a vector of path costs (e.g., the paths of a solution) should be combined into a single cost that reflects the cost of the entire path group together
- model::M<:AbstractCostModel{T} defines how the cost is computed during low
level search (when individual paths are being compared against each other).
CRCBS.GraphEnv — TypeGraphEnv{S,A,C} <: AbstractLowLevelEnv{S,A,C}An abstract environment type whose concrete subtypes comply with a standard interface.
CRCBS.HardConflictTable — TypeHardConflictTableStores a lookup table of planned paths for all agents. When agent i queries the table, table.paths[i] (the existing path plan for agent i) must be subtracted so that the agent does not try to avoid conflicts with itself.
CRCBS.LowLevelCostModel — TypeLowLevelCostModel{C}The low level cost model defines the objective to be optimized by the solver at the low level. An optimal low level solver will return a path if a feasible path exists) of minimal cost under the objective specified by the associated LowLevelCostModel. The parameter C defines the cost_type of the objective. The following functions must be implemented for a LowLevelCostModel to be used:
get_initial_cost(model::LowLevelCostModel,env)- returns
the initial_cost for a path
get_transition_cost(model::LowLevelCostModel{C},path::Path,s::S,a::A, sp::S) where {S,A,C}- defines the cost associated with taking actionafrom statesto arrive in statespaccording to the objective defined bymodelgiven thatsis the "tip" ofpath.accumulate_cost(model::LowLevelCostModel{C}, current_cost::C, transition_cost::C)- defines how cost accumulates as newPathNodes are added to a Path.
CRCBS.LowLevelSearchHeuristic — TypeLowLevelSearchHeuristic{C} <: AbstractCostModel{C}Abstract type of a heuristic that returns cost of type C.
CRCBS.MetaCost — TypeMetaCostMetaCost maintaining separate costs for individual agents that have been combined into a MetaAgent.
- independent_costs::Vector{T} a vector of costs, 1 per agent
- total_cost::T the total cost, which reflects the combined cost (its interpretation depends on the
MetaCostModelused to define cost- upating behavior)
CRCBS.MetaSolution — TypeMetaSolution{S}Wrapper for a LowLevelSolution that allows for keeping track of groups.
CRCBS.MultiDeadlineCost — TypeMultiDeadlineCostCombines multiple deadlines according to some specified aggregation function.
CRCBS.MultiStageEnvDistanceHeuristic — TypeMultiStageEnvDistanceHeuristic <: LowLevelSearchHeuristic{Float64}m.dists[i][stage] stores the distance from that stage's goal to the final stage's goal for agent i. The heuristic cost is computed as follows:
h = get_heuristic_cost(m.h,env,s) + cost_from_stage()
CRCBS.NullCost — TypeNullCost <: LowLevelCostModel{Float64}Cost equal to 0.0.
CRCBS.PIBTCache — TypePIBTCache{S,A}Contains info to be passed along through recursive calls to the PIBT algorithm for multi-agent path planning. Info to be stored:
- current state of each agent (should be lined up at the same time step)
- priority of each agent
- the planned action (and associated next state) for each agent
- the search environment for each agent, which contains e.g., the agent's goal, costmodel, heuristicmodel, etc.
- a conflict table of sorts to indicate which states/actions are reserved
- countdown flags that identify which paths are "active". If pibt is operating
on a "ragged" plan, where some paths have been planned further into the future than others, it needs to ensure that planning does not continue for a given path until all of the other paths have "caught up" to it.
CRCBS.PIBTReservationTable — TypePIBTReservationTableCRCBS.ReservationTable — TypeReservationTableData structure for reserving resources over a time interval. The table stores a vector of reservations for each resource. When a new reservation is added to the table, it is inserted into the reservation vector associated to the requested resource.
CRCBS.ResourceReservation — TypeResourceReservationr::ResourceReservation encodes a that resource r.resource is reserved by agent r.agent_id over time interval r.interval.
CRCBS.SoftConflictTable — Typeconstruct_empty_lookup_table(graph,T::Int)Returns a soft lookup table to encode possible paths for each agent through graph. The argument T defines the time horizon of the lookup table.
CRCBS.SoftConflictTable — TypeSoftConflictTableCRCBS.SolverException — TypeSolverExceptionCustom exception type for tracking solver timeouts, etc.
CRCBS.TransformCostModel — TypeTransformCostModel{T,M<:LowLevelCostModel{T}} <: LowLevelCostModel{T}Applies a transformation to an underlying cost model. e.g., TransformCostModel(c->2*c, TravelTime())
CRCBS.a_star! — Methodastar!(env,startstate)
A generic implementation of the A* search algorithm that operates on an Environment and initial state.
args:
env::E <: AbstractLowLevelEnvstart_state
The following methods must be implemented:
- is_goal(env::E,s::S)
- checkterminationcriteria(env::E,cost::C,path::Path{S,A,C},state::S)
- getpossibleactions(env::E,s::S)
- getnextstate(env::E,s::S,a::A,sp::S)
- gettransitioncost(env::E,s::S,a::A)
- violates_constraints(env::E,s::S,path::Path{S,A,C})
CRCBS.a_star_impl! — MethodThe internal loop of the A* algorithm.
# g(n) = cost of the path from the start node to n,
# h(n) = heuristic estimate of cost from n to goal
# f(n) = g(n) + h(n)CRCBS.action_space_trait — Methodaction_space_trait(env)Defaults to DiscreteSpace
CRCBS.add_conflict! — Methodhelper to insert conflicts into ConflictTableCRCBS.add_constraint! — FunctionAdds a CBSConstraint to a DiscreteConstraintTable
CRCBS.add_constraint! — Methodadds a CBSConstraint to a ConstraintTreeNode
CRCBS.add_fat_path_to_table! — Functionadd_fat_path_to_table(CAT,fat_path)CRCBS.add_to_path! — Methodadd_to_path!(path,env,s,a,sp)Adds the new (s,a,sp) tuple and its cost (under env) to path.
CRCBS.aggregate_costs_meta — Methoda special version of aggregate_costs for the meta_envCRCBS.cbs! — MethodConflict-Based Search
Sharon et al 2012
https://www.aaai.org/ocs/index.php/AAAI/AAAI12/paper/viewFile/5062/5239CRCBS.cbs_branch! — Methodcbs_branch!(solver,mapf,node,conflict,priority_queue)Part of CBS interface. Defaults to splitting on the conflict and adding two nodes to the priority_queue, where each of the child nodes has one of the new complementary constraints.
CRCBS.cbs_bypass! — Methodcbs_bypass!(solver,mapf,node,conflict,priority_queue)Part of CBS interface. Defaults to false, but can be overridden to modify the priority_queue and/or bypass the branching step of CBS
CRCBS.cbs_update_conflict_table! — Methodcbs_update_conflict_table!(solver,mapf,node,constraint)Allows for flexible conflict-updating dispatch. This function is called within within the default cbs_branch!() method.
CRCBS.combine_agents! — Methodcombine_agents(conflict_table, groups::Vector{Vector{Int}})Helper for merging two (meta) agents into a meta-agent
CRCBS.compute_heuristic_cost — Methodcompute_heuristic_cost(env,cost,sp)Defaults to add_heuristic_cost(env,cost,get_heuristic_cost(env,sp)) Can be overridden so that state info can inform the heuristic cost directly.
CRCBS.compute_path_cost — Methodcompute_path_cost(model,env,path,i)Compute the cost of a path from scratch.
CRCBS.construct_config_dataframe — Methodconstruct_results_dataframe(loader,solver_config,config_template)Compile results at solver_config.results_path into a DataFrame based on the features stored in solver_config.feats
CRCBS.construct_empty_lookup_table — Methodconstruct_empty_lookup_table(G,T::Int)Returns an empty lookup table.
CRCBS.construct_results_dataframe — Methodconstruct_results_dataframe(loader,solver_config,config_template)Compile results at solver_config.results_path into a DataFrame based on the features stored in solver_config.feats
CRCBS.convert_to_vertex_lists — MethodHelper for displaying Paths
CRCBS.count_conflicts — Methodcount_conflicts(conflict_table::ConflictTable,i::Int,j::Int)helper for counting the number of conflicts between agent i and agent j
CRCBS.create_reservations — Functioncreate_reservations(env::GraphEnv,s,a,sp,t=-1)Generates three reservations as follows
t0 = get_t(s)
tF = get_t(sp)
t_mid = (t0+tF)/2
reservations = [
ResourceReservation{Int}(s_idx,get_agent_id(env), (t0, t_mid)),
ResourceReservation{Int}(a_idx,get_agent_id(env), (t0, tF)),
ResourceReservation{Int}(sp_idx,get_agent_id(env), (t_mid, tF)),
]In this way, the reservations for one path node will not interfere with those for the next path node.
CRCBS.create_reservations — Functioncreate_reservation(env,s,a,sp)Must be overriden for environment env and the relevant state / action types.
CRCBS.default_solution — Methoddefault_solution(solver, mapf::AbstractMAPF)Defines what is returned by the solver in case of failure to find a feasible solution.
CRCBS.deserialize — Functiondeserialize(env,idx,t=-1)Decodes an integer encoding of a state or action of type state_type(env) or action_type(env)
CRCBS.detect_action_conflict — MethodChecks for an ActionConflict between two Paths at time t
CRCBS.detect_action_conflict — MethodDetect an ActionConflict between two path nodes. Must be overridden for each specific path class
CRCBS.detect_conflicts! — Methodadd detected conflicts to conflict table
CRCBS.detect_conflicts! — Methodadd detected conflicts to conflict table
CRCBS.detect_conflicts! — Methoddetect conflicts between paths
CRCBS.detect_conflicts! — MethodPopulates a ConflictTable with all conflicts that occur in a given vector of paths. Conflict checking is performed in a pairwise fashion between all paths.
args:
- conflict_table a
ConflictTableto store the detected conflicts - paths: a list of
Paths, one for each individual agent - idxs (optional) a list of agent ids for which to check collisions against all other agents
CRCBS.detect_state_conflict — MethodChecks for a StateConflict between two Paths at time t
CRCBS.detect_state_conflict — MethodDetect a StateConflict between two path nodes. Must be overridden for each specific path class
CRCBS.extend_path! — Methodextend_path!(path,T)Extends path to match a given length T by adding PathNodes corresponding to waiting at the final state.
args:
- path the path to be extended
- the desired length of the new path
CRCBS.extend_path — Methodextend_path(path,T)Extends a copy of path to match a given length T by adding PathNodes corresponding to waiting at the final state.
args:
- path the path to be extended
- the desired length of the new path
CRCBS.generate_constraints_from_conflict — Methodgenerates a Vector of (State or Action) Constraints from a conflict
CRCBS.get_a — Methodget_aGet the action in a PathNode.
CRCBS.get_agent_idxs — Methodget_agent_idxs(solver,node,mapf,constraint)Part of CBS interface. Defaults to return the index of a single agent affected by a constraint. Can be overridden to return the index of e.g., a "meta-agent" (group of agents).
CRCBS.get_conflict_index — Methodget_conflict_index(cache,i,s,a,sp)Returns the index of an agent that currently occupies sp, or -1 if there is no such agent.
CRCBS.get_conflicting_paths — Methodget_conflicting_pathsOperates over a lookup table and returns a dictionary mapping path index to the time index at which the conflict occurred
CRCBS.get_conflicts — Methodhelper for retrieving conflicts associated with agents i and j
CRCBS.get_constraints — Methodretrieve constraints corresponding to this node and this path
CRCBS.get_cost_model — MethodOverride this method for when the cost model has arguments
CRCBS.get_fat_path — Methodget_fat_path(G,D,start_vtx,goal_vtx)returns a fat path through G from start_vtx to goal_vtx. Each set of vertices in the fat path contains all vertices with distance d1 from startvtx and distance d2 to goalvtx, where d1+d2 == the length of the shortest path(s) from start_vtx to goal_vtx
G is a graph, D is the distance matrix
CRCBS.get_fat_path_cost — Methodget_fat_path_cost(model,nodes)Returns a scalar cost value depending on typeof(model) and length(nodes).
get_fat_path_cost(m::FlatFPCost,nodes) = 1.0
get_fat_path_cost(m::NormalizedFPCost,nodes) = 1.0/length(nodes)CRCBS.get_infeasible_cost — Methodget_infeasible_cost(model)Part of cost model interface. Defaults to zero.
CRCBS.get_infeasible_solution — Methodget_infeasible_solutionCRCBS.get_initial_cost — Methodget_initial_cost(model)Part of cost model interface. Defaults to zero.
CRCBS.get_initial_solution — Methodget_initial_solutionCRCBS.get_level_set_nodes — Functionget_level_set_nodes(env,s,threshold,cost=get_initial_cost(env))Returns a vector of PathNodes, where the heuristic cost (according to env) of each node falls below threshold.
CRCBS.get_mdd_graph — Functionget_mdd_graph(env,s,threshold,cost=get_initial_cost(env))Construct a multi-level decision diagram (MDD) graph.
CRCBS.get_next_conflict — Methodget_next_conflict(conflict_table::ConflictTable)Returns the next conflict (temporally) that occurs in a conflict table
CRCBS.get_path_node — Methodreturns the PathNode (s,a,s') corresponding to step t of path
If t is greater than the length of path, the PathNode returned is (s,wait(s),s) corresponding to waiting at that node of the path.
path[t] is the path node that begins at t-1 and terminates at t
CRCBS.get_s — Methodget_sGet the first state in a PathNode.
CRCBS.get_sp — Methodget_spGet the next state in a PathNode.
CRCBS.handle_solver_exception — Methodhandle_solver_exceptionTakes care of printing SolverExceptions
CRCBS.hard_reset_solver! — Methodhard_reset_solver!(solver)To be called when no information (other than iteration and time limits) needs to be stored.
CRCBS.has_constraint — Methodhas_constraint(env,table,c::CBSConstraint)CRCBS.init_dataframe — Functioninit_dataframe(feats::Tuple)Instantiate an empty dataframe based on the names and types of feature extractors in feats.
CRCBS.init_mapf_2 — Methodswitch placesCRCBS.init_mapf_3 — MethodcongestedCRCBS.init_mapf_4 — Methodalmost switch corners. With the fat path heuristic, the paths should be:
- Robot 1: [1,5,9,13,14,15]
- Robot 2: [16,12,8,4,3,2]CRCBS.init_mapf_5 — Methodinit_mapf_5PIBT demo from paper. CBS fails to solve it even with 80000 iterations.
CRCBS.init_mapf_6 — MethodPIBT demo from paperCRCBS.init_mapf_7 — Methodinit_mapf_7Robot 3 has to get past robots 1 and 2.
CRCBS.init_mapf_8 — Methodinit_mapf_8Robots 1 and 2 have to get past robots 3 and 4. Requires about 660 iterations of regular CBS.
CRCBS.initialize_child_search_node — Methodinitialize_child_search_node(parent_node::ConstraintTreeNode)Initialize a new ConstraintTreeNode with the same solution and constraints as the parent node
CRCBS.initialize_root_node — Functioninitialize_root_nodeConstruct an empty ConstraintTreeNode from a AbstractMAPF instance
CRCBS.is_available — Methodis_availableReturns false if the proposed reservation is not available to any of the agent_ids
CRCBS.is_consistent — Methodis_consistent(solution,mapf)
Check if solution satisfies start and end constraintsCRCBS.is_valid — MethodChecks if a conflict is valid
CRCBS.low_level_search! — Methodlow_level_search!(
solver,
mapf::AbstractMAPF,
node::ConstraintTreeNode,
idxs=collect(1:num_agents(mapf)),
path_finder=a_star!)
Returns a low level solution for a MAPF with constraints. The heuristic
function for cost-to-go is user-defined and environment-specificCRCBS.num_actions — Functionnum_actions(env)Returns the cardinality of the single agent state space for an environment. If the state and action spaces are finite and discrete, a discrete constraint table may be used for fast lookup.
CRCBS.num_states — Functionnum_states(env)Returns the cardinality of the single agent state space for an environment. If the state and action spaces are finite and discrete, a discrete constraint table may be used for fast lookup.
CRCBS.partially_set_path! — Methodpartially_set_path!Only replaces the cached path from start_time to length(path). Useful if you want the remainder of the cached path to stay in the lookup table (i.e. for repairing an existing plan).
CRCBS.pibt_priority_law — Methodpibt_priority_law(solver,mapf,cache,i)Returns a value that will determine the priority of agent i relative to other agents. A lower value means higher priority.
CRCBS.pibt_step! — Functionpibt_step!(solver,mapf,i,j=-1)i is the id of the higher priority agent, j is the index of the lower priority agent.
CRCBS.populate_soft_lookup_table! — Functionpopulate_soft_lookup_table!(CAT,start_times,start_vtxs,goal_vtxs)CRCBS.profile_solver! — Methodprofile_solver!(solver,mapf)Profile solver on mapf: Returns
- solution, timer_results
CRCBS.recompute_cost — Functionrecompute_costRecompute the cost of path (according to env), beginning from initial cost c0.
CRCBS.reconstruct_path! — Methodreconstruct path by working backward from the terminal stateCRCBS.remove_constraint! — FunctionRemoves a CBSConstraint to a DiscreteConstraintTable
CRCBS.reserve! — Methodreserve!(table,reservation)Attempts to add a reservation to the table. If the reservation conflicts with an existing reservation, does nothing and returns false. If successful, returns true.
CRCBS.reserved_by — Methodreserved_byReturns the IDs of agents who have reserved a resource within a specific time window.
CRCBS.reset_solver! — Methodreset_solver!(solver)Resets iteration counts and start times, in addition to best cost and lower bound.
CRCBS.reset_undecided! — MethodFills undecided with all active agents (inactive agents have already selected their actions)
CRCBS.run_profiling — Methodrun_profiling(config,loader)Profile the performance of one or more solvers on a set of problems defined by files in a directory. Args:
config: A named tuple or struct with at least the following fields:problem_dir::String: path to problem files.solver_configs: A vector of objects, each of which has the fields:solver: a solver complying with the CRCBS interface.results_path::String: path at which to store results.
- feats : A vector of
Featureobjects, which defines the specific
Loader: Any kind of cache on whichload_problem(loader,problem_file)can be called.
CRCBS.search_constraints — Methodsearch_constraints(env,table,n::PathNode)Returns all CBSConstraints and CBSConstraints that match n, regardless of time.
CRCBS.serialize — Functionserialize(env,state,t=-1)Encodes a state or action as an integer
CRCBS.set_constraint! — FunctionSets a CBSConstraint value in a DiscreteConstraintTable
CRCBS.soft_reset_solver! — Methodsoft_reset_solver!(solver)Resets iteration counts and start times.
CRCBS.solve! — Methodsolve!(solver, args ...)Run the algorithm represented by solver on an instance of a Multi-Agent Path-Finding problem.
CRCBS.sorted_actions — Methodsorted_actions(env,s)Return a vector of actions sorted lowest cost to highest cost.
CRCBS.state_space_trait — Methodstate_space_trait(env)Defaults to DiscreteSpace
CRCBS.time_to_deadline — Methodtime_to_deadline(solver)time to deadline(solver) or runtime_limit(solver)–whichever is shorter.
CRCBS.trim_path! — Methodtrim_path!(env,path,T)Modify path to terminate at time step T. If length(path) < T, the path will be extended to time step T.
CRCBS.trim_solution! — Methodtrim_solution!Modify solution so that all paths terminate at time step T.
CRCBS.update_fat_path_conflict_table! — Methodupdate_conflict_table!(table,nodes)Updates a conflict table with a set of nodes.
CRCBS.wait — Functionwait(s)returns an action that corresponds to waiting at state s
CRCBS.write_results — Methodwrite_results(loader,solver_config,prob,problem_file,results)Write results results of profiling solver_config.solver on problem prob of name problem_name. Can be overloaded to dispatch on problem type when applicable.
GraphUtils.get_graph — MethodGraphUtils.get_graph(env::GraphEnv)Must be implemented for all concrete subtypes of GraphEnv
CRCBS.BenchmarkInterface.MovingAIBenchmarkFile — TypeMovingAIBenchmarkFilePoints to a TOML-formatted file that contains the following elements: scenario = "/path/to/scenario/file.scen" mapfile = "/path/to/map/file.map" bucketidx = 1 # an integer n_agents = 2 # an integer
Extension is .bm
CRCBS.BenchmarkInterface.ProblemLoader — TypeProblemLoaderCan be queried via get_problem(iterator,problem_filename) to return MAPF instances.
CRCBS.BenchmarkInterface.is_same_scenario_and_bucket — Methodis_same_scenario_and_bucket(config1,config2)Checks that two problem_configs are on the same scenario and bucket.
CRCBS.BenchmarkInterface.parse_map_file — Functionparse_map_fileParses a .map file (see citation below) into an indicator grid. Each cell of the map is encoded by one of the following characters: . - passable terrain G - passable terrain @ - out of bounds O - out of bounds T - trees (unpassable) S - swamp (passable from regular terrain) W - water (traversable, but not passable from terrain)
Returns an array of integers encoded as IMPASSABLE=>1, FREE=>0 (we treat only 'G', 'S', and '.' as free).
@article{sturtevant2012benchmarks, title={Benchmarks for Grid-Based Pathfinding}, author={Sturtevant, N.}, journal={Transactions on Computational Intelligence and AI in Games}, volume={4}, number={2}, pages={144 – 148}, year={2012}, url = {http://web.cs.du.edu/~sturtevant/papers/benchmarks.pdf}, }
CRCBS.BenchmarkInterface.parse_mapf_scenario — Functionparse_mapf_scenario(filename,map_path="")Parses a .scen file into a set of 'buckets', where each bucket contains a list of (start location,goal location) pairs. Each bucket can be used to instantiate MAPF instances some (or all) of these pairs. The benchmarking approach proposed on the benchmark website (https://www.movingai.com/benchmarks/index.html) is to start with a 2-agent MAPF for each bucket, and increase the number of agents until solver time out.
CRCBS.BenchmarkInterface.profile_with_skipping! — Methodprofile_with_skipping!(config,loader)Follow the Moving AI benchmarking paradigm, where problems are skipped if the solver has already failed on the same problem instance with fewer agents.