#include <astar_solver.h>
Public Types | |
typedef GraphT::Ptr | GraphPtr |
typedef boost::function< double(SolverNodePtr, GraphPtr)> | HeuristicFunction |
typedef boost::shared_ptr< AStarSolver > | Ptr |
typedef SolverNode< State, GraphT >::Ptr | SolverNodePtr |
typedef GraphT::StateT | State |
typedef GraphT::StateT::Ptr | StatePtr |
Public Types inherited from jsk_footstep_planner::BestFirstSearchSolver< GraphT > | |
typedef GraphT::Ptr | GraphPtr |
typedef std::priority_queue< SolverNodePtr, std::vector< SolverNodePtr >, std::greater< SolverNodePtr > > | OpenList |
typedef boost::shared_ptr< BestFirstSearchSolver > | Ptr |
typedef SolverNode< State, GraphT >::Ptr | SolverNodePtr |
typedef GraphT::StateT | State |
typedef GraphT::StateT::Ptr | StatePtr |
Public Types inherited from jsk_footstep_planner::Solver< GraphT > | |
typedef GraphT::Ptr | GraphPtr |
typedef boost::shared_ptr< Solver > | Ptr |
typedef boost::unordered_map< StatePtr, double > | SolveList |
typedef SolverNode< State, GraphT >::Ptr | SolverNodePtr |
typedef GraphT::StateT | State |
typedef GraphT::StateT::Ptr | StatePtr |
Protected Attributes | |
HeuristicFunction | heuristic_ |
Protected Attributes inherited from jsk_footstep_planner::BestFirstSearchSolver< GraphT > | |
OpenList | open_list_ |
Protected Attributes inherited from jsk_footstep_planner::Solver< GraphT > | |
SolveList | close_list_ |
GraphPtr | graph_ |
bool | verbose_ |
Definition at line 77 of file astar_solver.h.
typedef GraphT::Ptr jsk_footstep_planner::AStarSolver< GraphT >::GraphPtr |
Definition at line 115 of file astar_solver.h.
typedef boost::function<double(SolverNodePtr, GraphPtr)> jsk_footstep_planner::AStarSolver< GraphT >::HeuristicFunction |
Definition at line 117 of file astar_solver.h.
typedef boost::shared_ptr<AStarSolver> jsk_footstep_planner::AStarSolver< GraphT >::Ptr |
Definition at line 112 of file astar_solver.h.
typedef SolverNode<State, GraphT>::Ptr jsk_footstep_planner::AStarSolver< GraphT >::SolverNodePtr |
Definition at line 116 of file astar_solver.h.
typedef GraphT::StateT jsk_footstep_planner::AStarSolver< GraphT >::State |
Definition at line 114 of file astar_solver.h.
typedef GraphT::StateT::Ptr jsk_footstep_planner::AStarSolver< GraphT >::StatePtr |
Definition at line 113 of file astar_solver.h.
|
inline |
Definition at line 119 of file astar_solver.h.
|
inlinevirtual |
Reimplemented from jsk_footstep_planner::BestFirstSearchSolver< GraphT >.
Reimplemented in jsk_footstep_planner::FootstepAStarSolver< GraphT >.
Definition at line 120 of file astar_solver.h.
|
inlinevirtual |
Definition at line 125 of file astar_solver.h.
|
inlinevirtual |
Definition at line 130 of file astar_solver.h.
|
inlinevirtual |
Definition at line 135 of file astar_solver.h.
|
protected |
Definition at line 139 of file astar_solver.h.