#include <footstep_astar_solver.h>
Public Types | |
typedef GraphT::Ptr | GraphPtr |
typedef std::priority_queue< SolverNodePtr, std::vector< SolverNodePtr >, std::greater< SolverNodePtr > > | OpenList |
typedef boost::function< void(FootstepAStarSolver &, GraphPtr)> | ProfileFunction |
typedef boost::shared_ptr< FootstepAStarSolver > | Ptr |
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 | |
const double | cost_weight_ |
FootstepStateDiscreteCloseList | footstep_close_list_ |
const double | heuristic_weight_ |
bool | is_cancelled_ |
bool | is_set_profile_function_ |
unsigned int | loop_counter_ |
ProfileFunction | profile_function_ |
unsigned int | profile_period_ |
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 80 of file footstep_astar_solver.h.
typedef GraphT::Ptr jsk_footstep_planner::FootstepAStarSolver< GraphT >::GraphPtr |
Definition at line 118 of file footstep_astar_solver.h.
typedef std::priority_queue<SolverNodePtr, std::vector<SolverNodePtr>, std::greater<SolverNodePtr> > jsk_footstep_planner::FootstepAStarSolver< GraphT >::OpenList |
Definition at line 123 of file footstep_astar_solver.h.
typedef boost::function<void(FootstepAStarSolver&, GraphPtr)> jsk_footstep_planner::FootstepAStarSolver< GraphT >::ProfileFunction |
Definition at line 120 of file footstep_astar_solver.h.
typedef boost::shared_ptr<FootstepAStarSolver> jsk_footstep_planner::FootstepAStarSolver< GraphT >::Ptr |
Definition at line 115 of file footstep_astar_solver.h.
typedef SolverNode<State, GraphT>::Ptr jsk_footstep_planner::FootstepAStarSolver< GraphT >::SolverNodePtr |
Definition at line 119 of file footstep_astar_solver.h.
typedef GraphT::StateT jsk_footstep_planner::FootstepAStarSolver< GraphT >::State |
Definition at line 116 of file footstep_astar_solver.h.
typedef GraphT::StateT::Ptr jsk_footstep_planner::FootstepAStarSolver< GraphT >::StatePtr |
Definition at line 117 of file footstep_astar_solver.h.
|
inline |
Definition at line 124 of file footstep_astar_solver.h.
|
inlinevirtual |
Definition at line 246 of file footstep_astar_solver.h.
|
inlinevirtual |
Reimplemented from jsk_footstep_planner::BestFirstSearchSolver< GraphT >.
Definition at line 291 of file footstep_astar_solver.h.
|
inlinevirtual |
Definition at line 235 of file footstep_astar_solver.h.
|
inline |
Definition at line 270 of file footstep_astar_solver.h.
|
inlinevirtual |
Reimplemented from jsk_footstep_planner::Solver< GraphT >.
Definition at line 241 of file footstep_astar_solver.h.
|
inlinevirtual |
Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.
Definition at line 140 of file footstep_astar_solver.h.
|
inlinevirtual |
Definition at line 253 of file footstep_astar_solver.h.
|
inlinevirtual |
Definition at line 251 of file footstep_astar_solver.h.
|
inlinevirtual |
Reimplemented from jsk_footstep_planner::Solver< GraphT >.
Definition at line 260 of file footstep_astar_solver.h.
|
inline |
Definition at line 276 of file footstep_astar_solver.h.
|
inlinevirtual |
Definition at line 254 of file footstep_astar_solver.h.
|
inlinevirtual |
Reimplemented from jsk_footstep_planner::Solver< GraphT >.
Definition at line 148 of file footstep_astar_solver.h.
|
protected |
Definition at line 320 of file footstep_astar_solver.h.
|
protected |
Definition at line 316 of file footstep_astar_solver.h.
|
protected |
Definition at line 321 of file footstep_astar_solver.h.
|
protected |
Definition at line 322 of file footstep_astar_solver.h.
|
protected |
Definition at line 315 of file footstep_astar_solver.h.
|
protected |
Definition at line 312 of file footstep_astar_solver.h.
|
protected |
Definition at line 314 of file footstep_astar_solver.h.
|
protected |
Definition at line 313 of file footstep_astar_solver.h.