CL-CBS
Classes | Public Member Functions | List of all members
libMultiRobotPlanning::CL_CBS< State, Action, Cost, Conflict, Constraints, Environment > Class Template Reference

Car-Like Conflict-Based Search(CL-CBS) algorithm to solve the Multi-Agent Path Finding for Car-Like robots (CL-MAPF) problem. More...

#include <cl_cbs.hpp>

Public Member Functions

 CL_CBS (Environment &environment)
 
 ~CL_CBS ()
 
bool search (const std::vector< State > &initialStates, std::vector< PlanResult< State, Action, Cost >> &solution)
 

Detailed Description

template<typename State, typename Action, typename Cost, typename Conflict, typename Constraints, typename Environment>
class libMultiRobotPlanning::CL_CBS< State, Action, Cost, Conflict, Constraints, Environment >

Car-Like Conflict-Based Search(CL-CBS) algorithm to solve the Multi-Agent Path Finding for Car-Like robots (CL-MAPF) problem.

It applies a body conflict tree to address collisions considering shapes of the agents. It uses a new algorithm called Spatiotemporal Hybrid-State A* as the single-agent path planner to generate path satisfying both kinematic and spatiotemporal constraints. The file also integrates a sequential planning version of CL-CBS method for the sake of efficiency.

Details of the algorithm can be found in the following paper:
Licheng Wen, Zhen Zhang, Zhe Chen, Xiangrui Zhao, and Yong Liu. CL-MAPF: Multi-Agent Path Finding for Car-Like Robots with Kinematic and Spatiotemporal Constraints.[arxiv]

Template Parameters
StateCustom state for the search. Needs to be copy'able
ActionCustom action for the search. Needs to be copy'able
CostCustom Cost type (integer or floating point types)
ConflictCustom conflict description. A conflict needs to be able to be transformed into a constraint.
ConstraintsCustom constraint description. The Environment needs to be able to search on the low-level while taking the constraints into account.
EnvironmentThis class needs to provide the custom logic. In particular, it needs to support the following functions:
  • void setLowLevelContext(size_t agentIdx, const Constraints* constraints)
    Set the current context to a particular agent with the given set of constraints
  • Cost admissibleHeuristic(const State& s)
    Admissible heuristic. Needs to take current context into account.
  • bool isSolution(const State& s, Cost gscore, std::unordered_map<State, std::tuple<State, Action, Cost, Cost>, StateHasher>& cameFrom)
    Return true if the given state is a goal state for the current agent. Add analatic expansion into camefrom struct.
  • void getNeighbors(const State& s, std::vector<Neighbor<State, Action, int> >& neighbors)
    Fill the list of neighboring state for the given state s and the current agent.
  • bool getFirstConflict(const std::vector<PlanResult<State, Action, int> >& solution, Conflict& result)
    Finds the first body conflict for the given solution for each agent. Return true if a conflict conflict was found and false otherwise.
  • void createConstraintsFromConflict(const Conflict& conflict, std::map<size_t, Constraints>& constraints)
    Create a list of constraints for the given conflict.
  • void onExpandHighLevelNode(Cost cost)
    This function is called on every high-level expansion and can be used for statistical purposes.
  • void onExpandLowLevelNode(const State& s, Cost fScore, Cost gScore)
    This function is called on every low-level expansion and can be used for statistical purposes.
Examples:
cl_cbs.cpp.

Constructor & Destructor Documentation

template<typename State , typename Action , typename Cost , typename Conflict , typename Constraints , typename Environment >
libMultiRobotPlanning::CL_CBS< State, Action, Cost, Conflict, Constraints, Environment >::CL_CBS ( Environment environment)
inline
template<typename State , typename Action , typename Cost , typename Conflict , typename Constraints , typename Environment >
libMultiRobotPlanning::CL_CBS< State, Action, Cost, Conflict, Constraints, Environment >::~CL_CBS ( )
inline

Member Function Documentation

template<typename State , typename Action , typename Cost , typename Conflict , typename Constraints , typename Environment >
bool libMultiRobotPlanning::CL_CBS< State, Action, Cost, Conflict, Constraints, Environment >::search ( const std::vector< State > &  initialStates,
std::vector< PlanResult< State, Action, Cost >> &  solution 
)
inline

The documentation for this class was generated from the following file: