#include <footstep_astar_solver.h>
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 < FootstepAStarSolver > | Ptr |
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 > ::Ptr > | solve (const ros::WallDuration &timeout=ros::WallDuration(1000000000.0)) |
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_ |
Definition at line 48 of file footstep_astar_solver.h.
typedef GraphT::Ptr jsk_footstep_planner::FootstepAStarSolver< GraphT >::GraphPtr |
Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.
Definition at line 54 of file footstep_astar_solver.h.
typedef std::priority_queue<SolverNodePtr, std::vector<SolverNodePtr>, std::greater<SolverNodePtr> > jsk_footstep_planner::FootstepAStarSolver< GraphT >::OpenList |
Reimplemented from jsk_footstep_planner::BestFirstSearchSolver< GraphT >.
Definition at line 59 of file footstep_astar_solver.h.
typedef boost::function<void(FootstepAStarSolver&, GraphPtr)> jsk_footstep_planner::FootstepAStarSolver< GraphT >::ProfileFunction |
Definition at line 56 of file footstep_astar_solver.h.
typedef boost::shared_ptr<FootstepAStarSolver> jsk_footstep_planner::FootstepAStarSolver< GraphT >::Ptr |
Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.
Definition at line 51 of file footstep_astar_solver.h.
typedef SolverNode<State, GraphT>::Ptr jsk_footstep_planner::FootstepAStarSolver< GraphT >::SolverNodePtr |
Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.
Definition at line 55 of file footstep_astar_solver.h.
typedef GraphT::StateT jsk_footstep_planner::FootstepAStarSolver< GraphT >::State |
Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.
Definition at line 52 of file footstep_astar_solver.h.
typedef GraphT::StateT::Ptr jsk_footstep_planner::FootstepAStarSolver< GraphT >::StatePtr |
Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.
Definition at line 53 of file footstep_astar_solver.h.
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.
virtual void jsk_footstep_planner::FootstepAStarSolver< GraphT >::addToCloseList | ( | StatePtr | s | ) | [inline, virtual] |
Definition at line 182 of file footstep_astar_solver.h.
void jsk_footstep_planner::FootstepAStarSolver< GraphT >::addToOpenList | ( | SolverNodePtr | node | ) | [inline, virtual] |
Reimplemented from jsk_footstep_planner::BestFirstSearchSolver< GraphT >.
Definition at line 227 of file footstep_astar_solver.h.
virtual void jsk_footstep_planner::FootstepAStarSolver< GraphT >::cancelSolve | ( | ) | [inline, virtual] |
Definition at line 171 of file footstep_astar_solver.h.
void jsk_footstep_planner::FootstepAStarSolver< GraphT >::closeListToPointCloud | ( | pcl::PointCloud< PointT > & | output_cloud | ) | [inline] |
Definition at line 206 of file footstep_astar_solver.h.
virtual bool jsk_footstep_planner::FootstepAStarSolver< GraphT >::findInCloseList | ( | StatePtr | s | ) | [inline, virtual] |
Reimplemented from jsk_footstep_planner::Solver< GraphT >.
Definition at line 177 of file footstep_astar_solver.h.
virtual double jsk_footstep_planner::FootstepAStarSolver< GraphT >::fn | ( | SolverNodePtr | n | ) | [inline, virtual] |
Reimplemented from jsk_footstep_planner::AStarSolver< GraphT >.
Definition at line 76 of file footstep_astar_solver.h.
virtual FootstepStateDiscreteCloseList jsk_footstep_planner::FootstepAStarSolver< GraphT >::getCloseList | ( | ) | [inline, virtual] |
Definition at line 189 of file footstep_astar_solver.h.
virtual OpenList jsk_footstep_planner::FootstepAStarSolver< GraphT >::getOpenList | ( | ) | [inline, virtual] |
Definition at line 187 of file footstep_astar_solver.h.
virtual bool jsk_footstep_planner::FootstepAStarSolver< GraphT >::isOK | ( | const ros::WallTime & | start_time, |
const ros::WallDuration & | timeout | ||
) | [inline, virtual] |
Reimplemented from jsk_footstep_planner::Solver< GraphT >.
Definition at line 196 of file footstep_astar_solver.h.
void jsk_footstep_planner::FootstepAStarSolver< GraphT >::openListToPointCloud | ( | pcl::PointCloud< PointT > & | output_cloud | ) | [inline] |
Definition at line 212 of file footstep_astar_solver.h.
virtual void jsk_footstep_planner::FootstepAStarSolver< GraphT >::setProfileFunction | ( | ProfileFunction | f | ) | [inline, virtual] |
Definition at line 190 of file footstep_astar_solver.h.
virtual std::vector<typename SolverNode<State, GraphT>::Ptr> jsk_footstep_planner::FootstepAStarSolver< GraphT >::solve | ( | const ros::WallDuration & | timeout = ros::WallDuration(1000000000.0) | ) | [inline, virtual] |
Reimplemented from jsk_footstep_planner::Solver< GraphT >.
Definition at line 84 of file footstep_astar_solver.h.
const double jsk_footstep_planner::FootstepAStarSolver< GraphT >::cost_weight_ [protected] |
Definition at line 256 of file footstep_astar_solver.h.
FootstepStateDiscreteCloseList jsk_footstep_planner::FootstepAStarSolver< GraphT >::footstep_close_list_ [protected] |
Definition at line 252 of file footstep_astar_solver.h.
const double jsk_footstep_planner::FootstepAStarSolver< GraphT >::heuristic_weight_ [protected] |
Definition at line 257 of file footstep_astar_solver.h.
bool jsk_footstep_planner::FootstepAStarSolver< GraphT >::is_cancelled_ [protected] |
Definition at line 258 of file footstep_astar_solver.h.
bool jsk_footstep_planner::FootstepAStarSolver< GraphT >::is_set_profile_function_ [protected] |
Definition at line 251 of file footstep_astar_solver.h.
unsigned int jsk_footstep_planner::FootstepAStarSolver< GraphT >::loop_counter_ [protected] |
Definition at line 248 of file footstep_astar_solver.h.
ProfileFunction jsk_footstep_planner::FootstepAStarSolver< GraphT >::profile_function_ [protected] |
Definition at line 250 of file footstep_astar_solver.h.
unsigned int jsk_footstep_planner::FootstepAStarSolver< GraphT >::profile_period_ [protected] |
Definition at line 249 of file footstep_astar_solver.h.