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

#include <footstep_astar_solver.h>

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

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< FootstepAStarSolverPtr
 
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< 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

virtual void addToCloseList (StatePtr s)
 
void addToOpenList (SolverNodePtr node)
 
virtual void cancelSolve ()
 
template<class PointT >
void closeListToPointCloud (pcl::PointCloud< PointT > &output_cloud)
 
virtual bool findInCloseList (StatePtr s)
 
virtual double fn (SolverNodePtr n)
 
 FootstepAStarSolver (GraphPtr graph, size_t x_num, size_t y_num, size_t theta_num, unsigned int profile_period=1024, double cost_weight=1.0, double heuristic_weight=1.0)
 
virtual FootstepStateDiscreteCloseList getCloseList ()
 
virtual OpenList getOpenList ()
 
virtual bool isOK (const ros::WallTime &start_time, const ros::WallDuration &timeout)
 
template<class PointT >
void openListToPointCloud (pcl::PointCloud< PointT > &output_cloud)
 
virtual void setProfileFunction (ProfileFunction f)
 
virtual std::vector< typename SolverNode< State, GraphT >::Ptrsolve (const ros::WallDuration &timeout=ros::WallDuration(1000000000.0))
 
- Public Member Functions inherited from jsk_footstep_planner::AStarSolver< GraphT >
 AStarSolver (GraphPtr graph)
 
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 >
 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, double &cost)
 
virtual bool removeFromCloseList (StatePtr state)
 
virtual void setVerbose (bool v)
 
 Solver ()
 
 Solver (GraphPtr graph)
 

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_
 

Detailed Description

template<class GraphT>
class jsk_footstep_planner::FootstepAStarSolver< GraphT >

Definition at line 48 of file footstep_astar_solver.h.

Member Typedef Documentation

◆ GraphPtr

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

Definition at line 54 of file footstep_astar_solver.h.

◆ OpenList

template<class GraphT>
typedef std::priority_queue<SolverNodePtr, std::vector<SolverNodePtr>, std::greater<SolverNodePtr> > jsk_footstep_planner::FootstepAStarSolver< GraphT >::OpenList

Definition at line 59 of file footstep_astar_solver.h.

◆ ProfileFunction

template<class GraphT>
typedef boost::function<void(FootstepAStarSolver&, GraphPtr)> jsk_footstep_planner::FootstepAStarSolver< GraphT >::ProfileFunction

Definition at line 56 of file footstep_astar_solver.h.

◆ Ptr

Definition at line 51 of file footstep_astar_solver.h.

◆ SolverNodePtr

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

Definition at line 55 of file footstep_astar_solver.h.

◆ State

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

Definition at line 52 of file footstep_astar_solver.h.

◆ StatePtr

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

Definition at line 53 of file footstep_astar_solver.h.

Constructor & Destructor Documentation

◆ FootstepAStarSolver()

template<class GraphT>
jsk_footstep_planner::FootstepAStarSolver< GraphT >::FootstepAStarSolver ( GraphPtr  graph,
size_t  x_num,
size_t  y_num,
size_t  theta_num,
unsigned int  profile_period = 1024,
double  cost_weight = 1.0,
double  heuristic_weight = 1.0 
)
inline

Definition at line 60 of file footstep_astar_solver.h.

Member Function Documentation

◆ addToCloseList()

template<class GraphT>
virtual void jsk_footstep_planner::FootstepAStarSolver< GraphT >::addToCloseList ( StatePtr  s)
inlinevirtual

Definition at line 182 of file footstep_astar_solver.h.

◆ addToOpenList()

template<class GraphT>
void jsk_footstep_planner::FootstepAStarSolver< GraphT >::addToOpenList ( SolverNodePtr  node)
inlinevirtual

◆ cancelSolve()

template<class GraphT>
virtual void jsk_footstep_planner::FootstepAStarSolver< GraphT >::cancelSolve ( )
inlinevirtual

Definition at line 171 of file footstep_astar_solver.h.

◆ closeListToPointCloud()

template<class GraphT>
template<class PointT >
void jsk_footstep_planner::FootstepAStarSolver< GraphT >::closeListToPointCloud ( pcl::PointCloud< PointT > &  output_cloud)
inline

Definition at line 206 of file footstep_astar_solver.h.

◆ findInCloseList()

template<class GraphT>
virtual bool jsk_footstep_planner::FootstepAStarSolver< GraphT >::findInCloseList ( StatePtr  s)
inlinevirtual

Reimplemented from jsk_footstep_planner::Solver< GraphT >.

Definition at line 177 of file footstep_astar_solver.h.

◆ fn()

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

Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.

Definition at line 76 of file footstep_astar_solver.h.

◆ getCloseList()

template<class GraphT>
virtual FootstepStateDiscreteCloseList jsk_footstep_planner::FootstepAStarSolver< GraphT >::getCloseList ( )
inlinevirtual

Definition at line 189 of file footstep_astar_solver.h.

◆ getOpenList()

template<class GraphT>
virtual OpenList jsk_footstep_planner::FootstepAStarSolver< GraphT >::getOpenList ( )
inlinevirtual

Definition at line 187 of file footstep_astar_solver.h.

◆ isOK()

template<class GraphT>
virtual bool jsk_footstep_planner::FootstepAStarSolver< GraphT >::isOK ( const ros::WallTime start_time,
const ros::WallDuration timeout 
)
inlinevirtual

Reimplemented from jsk_footstep_planner::Solver< GraphT >.

Definition at line 196 of file footstep_astar_solver.h.

◆ openListToPointCloud()

template<class GraphT>
template<class PointT >
void jsk_footstep_planner::FootstepAStarSolver< GraphT >::openListToPointCloud ( pcl::PointCloud< PointT > &  output_cloud)
inline

Definition at line 212 of file footstep_astar_solver.h.

◆ setProfileFunction()

template<class GraphT>
virtual void jsk_footstep_planner::FootstepAStarSolver< GraphT >::setProfileFunction ( ProfileFunction  f)
inlinevirtual

Definition at line 190 of file footstep_astar_solver.h.

◆ solve()

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

Reimplemented from jsk_footstep_planner::Solver< GraphT >.

Definition at line 84 of file footstep_astar_solver.h.

Member Data Documentation

◆ cost_weight_

template<class GraphT>
const double jsk_footstep_planner::FootstepAStarSolver< GraphT >::cost_weight_
protected

Definition at line 256 of file footstep_astar_solver.h.

◆ footstep_close_list_

template<class GraphT>
FootstepStateDiscreteCloseList jsk_footstep_planner::FootstepAStarSolver< GraphT >::footstep_close_list_
protected

Definition at line 252 of file footstep_astar_solver.h.

◆ heuristic_weight_

template<class GraphT>
const double jsk_footstep_planner::FootstepAStarSolver< GraphT >::heuristic_weight_
protected

Definition at line 257 of file footstep_astar_solver.h.

◆ is_cancelled_

template<class GraphT>
bool jsk_footstep_planner::FootstepAStarSolver< GraphT >::is_cancelled_
protected

Definition at line 258 of file footstep_astar_solver.h.

◆ is_set_profile_function_

template<class GraphT>
bool jsk_footstep_planner::FootstepAStarSolver< GraphT >::is_set_profile_function_
protected

Definition at line 251 of file footstep_astar_solver.h.

◆ loop_counter_

template<class GraphT>
unsigned int jsk_footstep_planner::FootstepAStarSolver< GraphT >::loop_counter_
protected

Definition at line 248 of file footstep_astar_solver.h.

◆ profile_function_

template<class GraphT>
ProfileFunction jsk_footstep_planner::FootstepAStarSolver< GraphT >::profile_function_
protected

Definition at line 250 of file footstep_astar_solver.h.

◆ profile_period_

template<class GraphT>
unsigned int jsk_footstep_planner::FootstepAStarSolver< GraphT >::profile_period_
protected

Definition at line 249 of file footstep_astar_solver.h.


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


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Sun May 28 2023 03:03:20