#include <solver.h>
Public Types | |
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 |
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_ |
typedef GraphT::Ptr jsk_footstep_planner::Solver< GraphT >::GraphPtr |
typedef boost::shared_ptr<Solver> jsk_footstep_planner::Solver< GraphT >::Ptr |
typedef boost::unordered_map< StatePtr, double > jsk_footstep_planner::Solver< GraphT >::SolveList |
typedef SolverNode<State, GraphT>::Ptr jsk_footstep_planner::Solver< GraphT >::SolverNodePtr |
typedef GraphT::StateT jsk_footstep_planner::Solver< GraphT >::State |
typedef GraphT::StateT::Ptr jsk_footstep_planner::Solver< GraphT >::StatePtr |
|
inline |
|
inline |
|
inlinevirtual |
|
pure virtual |
|
inlinevirtual |
|
inlinevirtual |
Reimplemented in jsk_footstep_planner::FootstepAStarSolver< GraphT >.
|
inlinevirtual |
|
inlinevirtual |
Reimplemented in jsk_footstep_planner::FootstepAStarSolver< GraphT >.
|
pure virtual |
|
pure virtual |
|
inlinevirtual |
|
inlinevirtual |
|
inlinevirtual |
|
protected |
|
protected |
|
protected |