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

Spatiotemporal Hybrid A* Algorithm. More...

#include <hybrid_astar.hpp>

Public Member Functions

 HybridAStar (Environment &environment)
 
 ~HybridAStar ()
 
bool search (const State &startState, PlanResult< State, Action, Cost > &solution, Cost initialCost=0)
 

Detailed Description

template<typename State, typename Action, typename Cost, typename Environment, typename StateHasher = std::hash<State>>
class libMultiRobotPlanning::HybridAStar< State, Action, Cost, Environment, StateHasher >

Spatiotemporal Hybrid A* Algorithm.

This class implements the Spatiotemporal Hybrid-State A* algorithm. Noted that it could also used as traditional Hybrid-State Astar using correct implementation

This class can either use a fibonacci heap, or a d-ary heap. The former is the default. Comment "USE_FIBONACCI_HEAP" to use the d-ary heap instead.

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)
EnvironmentThis class needs to provide the custom hybrid A* logic. In particular, it needs to support the following functions:
  • Cost admissibleHeuristic(const State& s)
    This function can return 0 if no suitable heuristic is available.
  • 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 close to goal state and it has a collision-free path to goal. It is also needed to insert the generate path-to-goal into the current cameFrom map.
  • State getGoal()
    Return goal state of current agent.
  • void getNeighbors(const State& s, std::vector<Neighbor<State, Action, Cost> >& neighbors)
    Fill the list of neighboring state for the given state s.
  • int calcIndex(const State& s)
    This function calculate a index(int) for a given state s, the index uses as a key in closed list.
  • void onExpandNode(const State& s, Cost fScore, Cost gScore)
    This function is called on every expansion and can be used for statistical purposes.
  • void onDiscover(const State& s, Cost fScore, Cost gScore)
    This function is called on every node discovery and can be used for statistical purposes.
StateHasherA class to convert a state to a hash value. Default: std::hash<State>
Examples:
sh_astar.cpp.

Constructor & Destructor Documentation

template<typename State, typename Action, typename Cost, typename Environment, typename StateHasher = std::hash<State>>
libMultiRobotPlanning::HybridAStar< State, Action, Cost, Environment, StateHasher >::HybridAStar ( Environment environment)
inline
template<typename State, typename Action, typename Cost, typename Environment, typename StateHasher = std::hash<State>>
libMultiRobotPlanning::HybridAStar< State, Action, Cost, Environment, StateHasher >::~HybridAStar ( )
inline

Member Function Documentation

template<typename State, typename Action, typename Cost, typename Environment, typename StateHasher = std::hash<State>>
bool libMultiRobotPlanning::HybridAStar< State, Action, Cost, Environment, StateHasher >::search ( const State &  startState,
PlanResult< State, Action, Cost > &  solution,
Cost  initialCost = 0 
)
inline

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