Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef JSK_FOOTSTEP_PLANNER_FOOTSTEP_SOLVER_H_
00038 #define JSK_FOOTSTEP_PLANNER_FOOTSTEP_SOLVER_H_
00039
00040 #include "jsk_footstep_planner/astar_solver.h"
00041 #include "jsk_footstep_planner/footstep_state_discrete_close_list.h"
00042
00043 namespace jsk_footstep_planner
00044 {
00045
00046
00047 template <class GraphT>
00048 class FootstepAStarSolver: public AStarSolver<GraphT>
00049 {
00050 public:
00051 typedef boost::shared_ptr<FootstepAStarSolver> Ptr;
00052 typedef typename GraphT::StateT State;
00053 typedef typename GraphT::StateT::Ptr StatePtr;
00054 typedef typename GraphT::Ptr GraphPtr;
00055 typedef typename SolverNode<State, GraphT>::Ptr SolverNodePtr;
00056 typedef typename boost::function<void(FootstepAStarSolver&, GraphPtr)> ProfileFunction;
00057 typedef typename std::priority_queue<SolverNodePtr,
00058 std::vector<SolverNodePtr>,
00059 std::greater<SolverNodePtr> > OpenList;
00060 FootstepAStarSolver(
00061 GraphPtr graph, size_t x_num, size_t y_num, size_t theta_num,
00062 unsigned int profile_period = 1024,
00063 double cost_weight = 1.0,
00064 double heuristic_weight = 1.0):
00065 footstep_close_list_(x_num, y_num, theta_num),
00066 profile_period_(profile_period),
00067 is_set_profile_function_(false),
00068 cost_weight_(cost_weight),
00069 heuristic_weight_(heuristic_weight),
00070 AStarSolver<GraphT>(graph)
00071 {
00072
00073 }
00074
00075 virtual double fn(SolverNodePtr n)
00076 {
00077 return cost_weight_ * gn(n) + heuristic_weight_ * hn(n);
00078 }
00079
00080
00081 virtual
00082 std::vector<typename SolverNode<State, GraphT>::Ptr>
00083 solve(const ros::WallDuration& timeout = ros::WallDuration(1000000000.0))
00084 {
00085 ros::WallTime start_time = ros::WallTime::now();
00086 SolverNodePtr start_state(new SolverNode<State, GraphT>(
00087 graph_->getStartState(),
00088 0, graph_));
00089 TransitionLimit::Ptr limit = graph_->getTransitionLimit();
00090 bool lazy_projection = graph_->lazyProjection();
00091 addToOpenList(start_state);
00092 while (!isOpenListEmpty() && isOK(start_time, timeout)) {
00093 SolverNodePtr target_node = popFromOpenList();
00094 if (graph_->usePointCloudModel() && lazy_projection) {
00095 unsigned int error_state;
00096 FootstepState::Ptr projected_state = graph_->projectFootstep(target_node->getState(),
00097 error_state);
00098 if (!projected_state) {
00099 if (graph_->localMovement() && error_state == projection_state::close_to_success) {
00100 std::vector<SolverNodePtr> locally_moved_nodes
00101 = target_node->wrapWithSolverNodes(target_node->getParent(),
00102 graph_->localMoveFootstepState(projected_state));
00103
00104 if (limit && target_node->getParent()) {
00105 for (size_t i = 0; i < locally_moved_nodes.size(); i++) {
00106 if (limit->check(target_node->getParent()->getState(),
00107 locally_moved_nodes[i]->getState())) {
00108 addToOpenList(locally_moved_nodes[i]);
00109 }
00110 }
00111 }
00112 else {
00113 addToOpenList(locally_moved_nodes);
00114 }
00115 }
00116 continue;
00117 }
00118 else {
00119 if (limit &&
00120 target_node->getParent() &&
00121 !limit->check(target_node->getParent()->getState(), projected_state)) {
00122 continue;
00123 }
00124 target_node->setState(projected_state);
00125 }
00126 }
00127 if (graph_->isGoal(target_node->getState())) {
00128 if (is_set_profile_function_) {
00129 profile_function_(*this, graph_);
00130 }
00131 std::vector<SolverNodePtr> result_path = target_node->getPathWithoutThis();
00132 result_path.push_back(target_node);
00133 return result_path;
00134 }
00135 else if (!findInCloseList(target_node->getState())) {
00136 addToCloseList(target_node->getState());
00137 std::vector<SolverNodePtr> next_nodes = target_node->expand(target_node, verbose_);
00138
00139
00140 for (size_t i = 0; i < next_nodes.size(); i++) {
00141 SolverNodePtr next_node = next_nodes[i];
00142 if (!findInCloseList(next_node->getState())) {
00143 addToOpenList(next_node);
00144 }
00145 }
00146 }
00147 }
00148
00149 return std::vector<SolverNodePtr>();
00150 }
00151
00152
00153 virtual bool findInCloseList(StatePtr s)
00154 {
00155 return footstep_close_list_.find(s);
00156 }
00157
00158 virtual void addToCloseList(StatePtr s)
00159 {
00160 footstep_close_list_.push_back(s);
00161 }
00162
00163 virtual OpenList getOpenList() { return open_list_; }
00164
00165 virtual FootstepStateDiscreteCloseList getCloseList() { return footstep_close_list_; }
00166 virtual void setProfileFunction(ProfileFunction f)
00167 {
00168 profile_function_ = f;
00169 is_set_profile_function_ = true;
00170 }
00171
00172 virtual bool isOK(const ros::WallTime& start_time, const ros::WallDuration& timeout)
00173 {
00174 if (is_set_profile_function_ && ++loop_counter_ % profile_period_ == 0) {
00175 profile_function_(*this, graph_);
00176 loop_counter_ = 0;
00177 }
00178 return (ros::ok() && (ros::WallTime::now() - start_time) < timeout);
00179 }
00180
00181 template <class PointT>
00182 void closeListToPointCloud(pcl::PointCloud<PointT>& output_cloud)
00183 {
00184 footstep_close_list_.toPointCloud<PointT>(output_cloud);
00185 }
00186
00187 template <class PointT>
00188 void openListToPointCloud(pcl::PointCloud<PointT>& output_cloud)
00189 {
00190 output_cloud.points.reserve(open_list_.size());
00191 OpenList copied_open_list = open_list_;
00192
00193 while (copied_open_list.size() > 0)
00194 {
00195 SolverNodePtr solver_node = copied_open_list.top();
00196 StatePtr state = solver_node->getState();
00197 PointT p = ((FootstepState::Ptr)state)->toPoint<PointT>();
00198 output_cloud.points.push_back(p);
00199 copied_open_list.pop();
00200 }
00201 }
00202
00203 void addToOpenList(SolverNodePtr node)
00204 {
00205 if (node->isRoot()) {
00206 BestFirstSearchSolver<GraphT>::addToOpenList(node);
00207 }
00208 else {
00209 if (node->getState()->crossCheck(
00210 node->getParent()->getState())) {
00211 BestFirstSearchSolver<GraphT>::addToOpenList(node);
00212 }
00213 }
00214 }
00215
00216 using Solver<GraphT>::isOpenListEmpty;
00217 using Solver<GraphT>::popFromOpenList;
00218 using Solver<GraphT>::addToOpenList;
00219 using BestFirstSearchSolver<GraphT>::addToOpenList;
00220 using AStarSolver<GraphT>::gn;
00221 using AStarSolver<GraphT>::hn;
00222
00223 protected:
00224 unsigned int loop_counter_;
00225 unsigned int profile_period_;
00226 ProfileFunction profile_function_;
00227 bool is_set_profile_function_;
00228 FootstepStateDiscreteCloseList footstep_close_list_;
00229 using Solver<GraphT>::graph_;
00230 using Solver<GraphT>::verbose_;
00231 using BestFirstSearchSolver<GraphT>::open_list_;
00232 const double cost_weight_;
00233 const double heuristic_weight_;
00234 };
00235 }
00236
00237 #endif