Public Types | Public Member Functions | Protected Attributes | List of all members
jsk_footstep_planner::AStarSolver< GraphT > Class Template Reference

#include <astar_solver.h>

Inheritance diagram for jsk_footstep_planner::AStarSolver< GraphT >:
Inheritance graph
[legend]

Public Types

typedef GraphT::Ptr GraphPtr
 
typedef boost::function< double(SolverNodePtr, GraphPtr)> HeuristicFunction
 
typedef boost::shared_ptr< AStarSolverPtr
 
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< BestFirstSearchSolverPtr
 
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< SolverPtr
 
typedef boost::unordered_map< StatePtr, double > SolveList
 
typedef SolverNode< State, GraphT >::Ptr SolverNodePtr
 
typedef GraphT::StateT State
 
typedef GraphT::StateT::Ptr StatePtr
 

Public Member Functions

 AStarSolver (GraphPtr graph)
 
virtual double fn (SolverNodePtr n)
 
virtual double gn (SolverNodePtr n)
 
virtual double hn (SolverNodePtr n)
 
virtual void setHeuristic (HeuristicFunction h)
 
- Public Member Functions inherited from jsk_footstep_planner::BestFirstSearchSolver< GraphT >
virtual void addToOpenList (SolverNodePtr node)
 
 BestFirstSearchSolver (GraphPtr graph)
 
virtual bool isOpenListEmpty ()
 
virtual SolverNodePtr popFromOpenList ()
 
- Public Member Functions inherited from jsk_footstep_planner::Solver< GraphT >
virtual void addToCloseList (StatePtr state, double cost=0)
 
virtual void addToOpenList (std::vector< SolverNodePtr > nodes)
 
virtual bool findInCloseList (StatePtr state)
 
virtual bool findInCloseList (StatePtr state, double &cost)
 
virtual bool isOK (const ros::WallTime &start_time, const ros::WallDuration &timeout)
 
virtual bool removeFromCloseList (StatePtr state)
 
virtual void setVerbose (bool v)
 
virtual std::vector< typename SolverNode< State, GraphT >::Ptrsolve (const ros::WallDuration &timeout=ros::WallDuration(1000000000.0))
 
 Solver ()
 
 Solver (GraphPtr graph)
 

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_
 

Detailed Description

template<class GraphT>
class jsk_footstep_planner::AStarSolver< GraphT >

Definition at line 45 of file astar_solver.h.

Member Typedef Documentation

template<class GraphT>
typedef GraphT::Ptr jsk_footstep_planner::AStarSolver< GraphT >::GraphPtr

Definition at line 51 of file astar_solver.h.

template<class GraphT>
typedef boost::function<double(SolverNodePtr, GraphPtr)> jsk_footstep_planner::AStarSolver< GraphT >::HeuristicFunction

Definition at line 53 of file astar_solver.h.

template<class GraphT>
typedef boost::shared_ptr<AStarSolver> jsk_footstep_planner::AStarSolver< GraphT >::Ptr

Definition at line 48 of file astar_solver.h.

template<class GraphT>
typedef SolverNode<State, GraphT>::Ptr jsk_footstep_planner::AStarSolver< GraphT >::SolverNodePtr

Definition at line 52 of file astar_solver.h.

template<class GraphT>
typedef GraphT::StateT jsk_footstep_planner::AStarSolver< GraphT >::State

Definition at line 50 of file astar_solver.h.

template<class GraphT>
typedef GraphT::StateT::Ptr jsk_footstep_planner::AStarSolver< GraphT >::StatePtr

Definition at line 49 of file astar_solver.h.

Constructor & Destructor Documentation

template<class GraphT>
jsk_footstep_planner::AStarSolver< GraphT >::AStarSolver ( GraphPtr  graph)
inline

Definition at line 55 of file astar_solver.h.

Member Function Documentation

template<class GraphT>
virtual double jsk_footstep_planner::AStarSolver< GraphT >::fn ( SolverNodePtr  n)
inlinevirtual
template<class GraphT>
virtual double jsk_footstep_planner::AStarSolver< GraphT >::gn ( SolverNodePtr  n)
inlinevirtual

Definition at line 61 of file astar_solver.h.

template<class GraphT>
virtual double jsk_footstep_planner::AStarSolver< GraphT >::hn ( SolverNodePtr  n)
inlinevirtual

Definition at line 66 of file astar_solver.h.

template<class GraphT>
virtual void jsk_footstep_planner::AStarSolver< GraphT >::setHeuristic ( HeuristicFunction  h)
inlinevirtual

Definition at line 71 of file astar_solver.h.

Member Data Documentation

template<class GraphT>
HeuristicFunction jsk_footstep_planner::AStarSolver< GraphT >::heuristic_
protected

Definition at line 75 of file astar_solver.h.


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


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Fri May 14 2021 02:51:52