#include <grid_astar_solver.h>
Public Types | |
typedef GraphT::Ptr | GraphPtr |
typedef std::vector< typename SolverNode< State, GraphT >::Ptr > | Path |
typedef boost::shared_ptr< GridAStarSolver > | Ptr |
typedef boost::unordered_map< StatePtr, SolverNodePtr > | SolveList |
typedef SolverNode< State, GraphT >::Ptr | SolverNodePtr |
typedef GraphT::StateT | State |
typedef GraphT::StateT::Ptr | StatePtr |
Public Types inherited from jsk_footstep_planner::AStarSolver< GraphT > | |
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 | |
SolveList | open_list_map_ |
Protected Attributes inherited from jsk_footstep_planner::AStarSolver< GraphT > | |
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 11 of file grid_astar_solver.h.
typedef GraphT::Ptr jsk_footstep_planner::GridAStarSolver< GraphT >::GraphPtr |
Definition at line 17 of file grid_astar_solver.h.
typedef std::vector<typename SolverNode<State, GraphT>::Ptr> jsk_footstep_planner::GridAStarSolver< GraphT >::Path |
Definition at line 19 of file grid_astar_solver.h.
typedef boost::shared_ptr<GridAStarSolver> jsk_footstep_planner::GridAStarSolver< GraphT >::Ptr |
Definition at line 14 of file grid_astar_solver.h.
typedef boost::unordered_map< StatePtr, SolverNodePtr > jsk_footstep_planner::GridAStarSolver< GraphT >::SolveList |
Definition at line 20 of file grid_astar_solver.h.
typedef SolverNode<State, GraphT>::Ptr jsk_footstep_planner::GridAStarSolver< GraphT >::SolverNodePtr |
Definition at line 18 of file grid_astar_solver.h.
typedef GraphT::StateT jsk_footstep_planner::GridAStarSolver< GraphT >::State |
Definition at line 15 of file grid_astar_solver.h.
typedef GraphT::StateT::Ptr jsk_footstep_planner::GridAStarSolver< GraphT >::StatePtr |
Definition at line 16 of file grid_astar_solver.h.
|
inline |
Definition at line 22 of file grid_astar_solver.h.
|
inlinevirtual |
Definition at line 146 of file grid_astar_solver.h.
|
inlinevirtual |
Reimplemented from jsk_footstep_planner::BestFirstSearchSolver< GraphT >.
Definition at line 111 of file grid_astar_solver.h.
|
inlinevirtual |
Definition at line 155 of file grid_astar_solver.h.
|
inlinevirtual |
Definition at line 123 of file grid_astar_solver.h.
|
inlinevirtual |
Definition at line 168 of file grid_astar_solver.h.
|
inlinevirtual |
Definition at line 164 of file grid_astar_solver.h.
|
inlinevirtual |
Reimplemented from jsk_footstep_planner::BestFirstSearchSolver< GraphT >.
Definition at line 87 of file grid_astar_solver.h.
|
inlinevirtual |
Reimplemented from jsk_footstep_planner::BestFirstSearchSolver< GraphT >.
Definition at line 91 of file grid_astar_solver.h.
|
inlinevirtual |
Definition at line 159 of file grid_astar_solver.h.
|
inlinevirtual |
Definition at line 133 of file grid_astar_solver.h.
|
inlinevirtual |
Reimplemented from jsk_footstep_planner::Solver< GraphT >.
Definition at line 26 of file grid_astar_solver.h.
|
protected |
Definition at line 174 of file grid_astar_solver.h.