Public Types | Public Member Functions | Protected Attributes
jsk_footstep_planner::GridAStarSolver< GraphT > Class Template Reference

#include <grid_astar_solver.h>

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

List of all members.

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 Member Functions

virtual void addToCloseList (SolverNodePtr node)
virtual void addToOpenList (SolverNodePtr node)
virtual bool findInCloseList (SolverNodePtr node, double &cost)
virtual bool findInOpenList (SolverNodePtr node, double &cost)
virtual bool getCloseList (std::vector< StatePtr > &lst, std::vector< float > &cost)
virtual bool getOpenList (std::vector< StatePtr > &lst, std::vector< float > &cost)
 GridAStarSolver (GraphPtr graph)
virtual bool isOpenListEmpty ()
virtual SolverNodePtr popFromOpenList ()
virtual bool removeFromCloseList (SolverNodePtr node)
virtual bool removeFromOpenList (SolverNodePtr node)
virtual std::vector< typename
SolverNode< State, GraphT >
::Ptr
solve (const ros::WallDuration &timeout=ros::WallDuration(1000000000.0))

Protected Attributes

SolveList open_list_map_

Detailed Description

template<class GraphT>
class jsk_footstep_planner::GridAStarSolver< GraphT >

Definition at line 11 of file grid_astar_solver.h.


Member Typedef Documentation

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

Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.

Definition at line 17 of file grid_astar_solver.h.

template<class GraphT >
typedef std::vector<typename SolverNode<State, GraphT>::Ptr> jsk_footstep_planner::GridAStarSolver< GraphT >::Path

Definition at line 19 of file grid_astar_solver.h.

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

Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.

Definition at line 14 of file grid_astar_solver.h.

template<class GraphT >
typedef boost::unordered_map< StatePtr, SolverNodePtr > jsk_footstep_planner::GridAStarSolver< GraphT >::SolveList

Reimplemented from jsk_footstep_planner::Solver< GraphT >.

Definition at line 20 of file grid_astar_solver.h.

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

Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.

Definition at line 18 of file grid_astar_solver.h.

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

Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.

Definition at line 15 of file grid_astar_solver.h.

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

Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.

Definition at line 16 of file grid_astar_solver.h.


Constructor & Destructor Documentation

template<class GraphT >
jsk_footstep_planner::GridAStarSolver< GraphT >::GridAStarSolver ( GraphPtr  graph) [inline]

Definition at line 22 of file grid_astar_solver.h.


Member Function Documentation

template<class GraphT >
virtual void jsk_footstep_planner::GridAStarSolver< GraphT >::addToCloseList ( SolverNodePtr  node) [inline, virtual]

Definition at line 146 of file grid_astar_solver.h.

template<class GraphT >
virtual void jsk_footstep_planner::GridAStarSolver< GraphT >::addToOpenList ( SolverNodePtr  node) [inline, virtual]

Reimplemented from jsk_footstep_planner::BestFirstSearchSolver< GraphT >.

Definition at line 111 of file grid_astar_solver.h.

template<class GraphT >
virtual bool jsk_footstep_planner::GridAStarSolver< GraphT >::findInCloseList ( SolverNodePtr  node,
double &  cost 
) [inline, virtual]

Definition at line 155 of file grid_astar_solver.h.

template<class GraphT >
virtual bool jsk_footstep_planner::GridAStarSolver< GraphT >::findInOpenList ( SolverNodePtr  node,
double &  cost 
) [inline, virtual]

Definition at line 123 of file grid_astar_solver.h.

template<class GraphT >
virtual bool jsk_footstep_planner::GridAStarSolver< GraphT >::getCloseList ( std::vector< StatePtr > &  lst,
std::vector< float > &  cost 
) [inline, virtual]

Definition at line 168 of file grid_astar_solver.h.

template<class GraphT >
virtual bool jsk_footstep_planner::GridAStarSolver< GraphT >::getOpenList ( std::vector< StatePtr > &  lst,
std::vector< float > &  cost 
) [inline, virtual]

Definition at line 164 of file grid_astar_solver.h.

template<class GraphT >
virtual bool jsk_footstep_planner::GridAStarSolver< GraphT >::isOpenListEmpty ( ) [inline, virtual]

Reimplemented from jsk_footstep_planner::BestFirstSearchSolver< GraphT >.

Definition at line 87 of file grid_astar_solver.h.

template<class GraphT >
virtual SolverNodePtr jsk_footstep_planner::GridAStarSolver< GraphT >::popFromOpenList ( ) [inline, virtual]

Reimplemented from jsk_footstep_planner::BestFirstSearchSolver< GraphT >.

Definition at line 91 of file grid_astar_solver.h.

template<class GraphT >
virtual bool jsk_footstep_planner::GridAStarSolver< GraphT >::removeFromCloseList ( SolverNodePtr  node) [inline, virtual]

Definition at line 159 of file grid_astar_solver.h.

template<class GraphT >
virtual bool jsk_footstep_planner::GridAStarSolver< GraphT >::removeFromOpenList ( SolverNodePtr  node) [inline, virtual]

Definition at line 133 of file grid_astar_solver.h.

template<class GraphT >
virtual std::vector<typename SolverNode<State, GraphT>::Ptr> jsk_footstep_planner::GridAStarSolver< GraphT >::solve ( const ros::WallDuration timeout = ros::WallDuration(1000000000.0)) [inline, virtual]

Reimplemented from jsk_footstep_planner::Solver< GraphT >.

Definition at line 26 of file grid_astar_solver.h.


Member Data Documentation

template<class GraphT >
SolveList jsk_footstep_planner::GridAStarSolver< GraphT >::open_list_map_ [protected]

Definition at line 174 of file grid_astar_solver.h.


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


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Wed Jul 19 2017 02:54:29