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

#include <solver.h>

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

List of all members.

Public Types

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

virtual void addToCloseList (StatePtr state, double cost=0)
virtual void addToOpenList (SolverNodePtr node)=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 isOpenListEmpty ()=0
virtual SolverNodePtr popFromOpenList ()=0
virtual bool removeFromCloseList (StatePtr state)
virtual void setVerbose (bool v)
virtual std::vector< typename
SolverNode< State, GraphT >
::Ptr
solve (const ros::WallDuration &timeout=ros::WallDuration(1000000000.0))
 Solver ()
 Solver (GraphPtr graph)

Protected Attributes

SolveList close_list_
GraphPtr graph_
bool verbose_

Detailed Description

template<class GraphT>
class jsk_footstep_planner::Solver< GraphT >

Definition at line 47 of file solver.h.


Member Typedef Documentation

template<class GraphT >
typedef GraphT::Ptr jsk_footstep_planner::Solver< GraphT >::GraphPtr
template<class GraphT >
typedef boost::shared_ptr<Solver> jsk_footstep_planner::Solver< GraphT >::Ptr
template<class GraphT >
typedef boost::unordered_map< StatePtr, double > jsk_footstep_planner::Solver< GraphT >::SolveList

Reimplemented in jsk_footstep_planner::GridAStarSolver< GraphT >.

Definition at line 55 of file solver.h.

template<class GraphT >
typedef SolverNode<State, GraphT>::Ptr jsk_footstep_planner::Solver< GraphT >::SolverNodePtr
template<class GraphT >
typedef GraphT::StateT jsk_footstep_planner::Solver< GraphT >::State
template<class GraphT >
typedef GraphT::StateT::Ptr jsk_footstep_planner::Solver< GraphT >::StatePtr

Constructor & Destructor Documentation

template<class GraphT >
jsk_footstep_planner::Solver< GraphT >::Solver ( ) [inline]

Definition at line 57 of file solver.h.

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

Definition at line 58 of file solver.h.


Member Function Documentation

template<class GraphT >
virtual void jsk_footstep_planner::Solver< GraphT >::addToCloseList ( StatePtr  state,
double  cost = 0 
) [inline, virtual]

Definition at line 103 of file solver.h.

template<class GraphT >
virtual void jsk_footstep_planner::Solver< GraphT >::addToOpenList ( SolverNodePtr  node) [pure virtual]
template<class GraphT >
virtual void jsk_footstep_planner::Solver< GraphT >::addToOpenList ( std::vector< SolverNodePtr nodes) [inline, virtual]

Definition at line 96 of file solver.h.

template<class GraphT >
virtual bool jsk_footstep_planner::Solver< GraphT >::findInCloseList ( StatePtr  state) [inline, virtual]

Reimplemented in jsk_footstep_planner::FootstepAStarSolver< GraphT >.

Definition at line 110 of file solver.h.

template<class GraphT >
virtual bool jsk_footstep_planner::Solver< GraphT >::findInCloseList ( StatePtr  state,
double &  cost 
) [inline, virtual]

Definition at line 114 of file solver.h.

template<class GraphT >
virtual bool jsk_footstep_planner::Solver< GraphT >::isOK ( const ros::WallTime start_time,
const ros::WallDuration timeout 
) [inline, virtual]

Reimplemented in jsk_footstep_planner::FootstepAStarSolver< GraphT >.

Definition at line 88 of file solver.h.

template<class GraphT >
virtual bool jsk_footstep_planner::Solver< GraphT >::isOpenListEmpty ( ) [pure virtual]
template<class GraphT >
virtual SolverNodePtr jsk_footstep_planner::Solver< GraphT >::popFromOpenList ( ) [pure virtual]
template<class GraphT >
virtual bool jsk_footstep_planner::Solver< GraphT >::removeFromCloseList ( StatePtr  state) [inline, virtual]

Definition at line 125 of file solver.h.

template<class GraphT >
virtual void jsk_footstep_planner::Solver< GraphT >::setVerbose ( bool  v) [inline, virtual]

Definition at line 60 of file solver.h.

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

Member Data Documentation

template<class GraphT >
SolveList jsk_footstep_planner::Solver< GraphT >::close_list_ [protected]

Definition at line 136 of file solver.h.

template<class GraphT >
GraphPtr jsk_footstep_planner::Solver< GraphT >::graph_ [protected]

Definition at line 137 of file solver.h.

template<class GraphT >
bool jsk_footstep_planner::Solver< GraphT >::verbose_ [protected]

Definition at line 138 of file solver.h.


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


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Fri Apr 19 2019 03:45:28