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_SOLVER_NODE_H_
00038 #define JSK_FOOTSTEP_PLANNER_SOLVER_NODE_H_
00039
00040 #include <algorithm>
00041 #include <iterator>
00042 #include <boost/shared_ptr.hpp>
00043 #include <boost/weak_ptr.hpp>
00044 #include "jsk_footstep_planner/graph.h"
00045 #include <ros/ros.h>
00046
00047 namespace jsk_footstep_planner
00048 {
00049 template <class StateT, class GraphT>
00050 class SolverNode
00051 {
00052 public:
00053 typedef boost::shared_ptr<SolverNode> Ptr;
00054 typedef boost::shared_ptr<StateT> StatePtr;
00055 typedef typename GraphT::Ptr GraphPtr;
00056 typedef typename boost::weak_ptr<GraphT> GraphWeakPtr;
00057
00058 SolverNode(StatePtr state, const double cost,
00059 Ptr parent, GraphPtr graph):
00060 cost_(cost), state_(state), parent_(parent), graph_(graph) {}
00061
00062
00063
00064 SolverNode(StatePtr state, const double cost, GraphPtr graph):
00065 cost_(cost), state_(state), graph_(graph) {}
00066
00067
00068
00069 virtual
00070 StatePtr getState() const { return state_; }
00071
00072 virtual
00073 std::vector<Ptr> wrapWithSolverNodes(Ptr this_ptr, std::vector<StatePtr> successors)
00074 {
00075 GraphPtr graph_ptr = graph_.lock();
00076 std::vector<Ptr> solver_nodes;
00077 for (size_t i = 0; i < successors.size(); i++) {
00078 StatePtr next_state = successors[i];
00079 SolverNode::Ptr solver_node(new SolverNode(
00080 next_state,
00081 graph_ptr->pathCost(state_, next_state, cost_),
00082 this_ptr,
00083 graph_ptr));
00084 solver_nodes.push_back(solver_node);
00085 }
00086 return solver_nodes;
00087 }
00088
00089 virtual
00090 std::vector<Ptr> expand(Ptr this_ptr, bool verbose)
00091 {
00092 GraphPtr graph_ptr = graph_.lock();
00093 std::vector<Ptr> solver_nodes;
00094 if (graph_ptr) {
00095 std::vector<StatePtr> successors = graph_ptr->successors(state_);
00096 if (verbose) {
00097 std::cerr << successors.size() << " successors" << std::endl;
00098 }
00099 return wrapWithSolverNodes(this_ptr, successors);
00100 }
00101 else {
00102
00103
00104 throw std::runtime_error("no graph is set in SolverNode");
00105 }
00106 return solver_nodes;
00107 }
00108
00109 bool isRoot() const { return !parent_; }
00110 double getCost() const { return cost_; }
00111 double getSortValue() const { return sort_value_; }
00112 void setGraph(GraphPtr graph) { graph_ = graph; }
00113 void setSortValue(double v) { sort_value_ = v; }
00114 void setCost(double c) { cost_ = c; }
00115
00116 std::vector<SolverNode::Ptr>
00117 getPathWithoutThis()
00118 {
00119 if (isRoot()) {
00120 return std::vector<SolverNode::Ptr>();
00121 }
00122 else {
00123 std::vector<SolverNode::Ptr> parent_path = parent_->getPathWithoutThis();
00124 parent_path.push_back(parent_);
00125 return parent_path;
00126 }
00127 }
00128
00129 virtual void setState(StatePtr state) { state_ = state; }
00130
00131 friend bool operator<(const SolverNode<StateT, GraphT>::Ptr a,
00132 const SolverNode<StateT, GraphT>::Ptr b)
00133 {
00134 return a->getSortValue() < b->getSortValue();
00135 }
00136
00137 friend bool operator>(const SolverNode<StateT, GraphT>::Ptr a,
00138 const SolverNode<StateT, GraphT>::Ptr b)
00139 {
00140 return a->getSortValue() > b->getSortValue();
00141 }
00142
00143 virtual Ptr getParent() const { return parent_; }
00144
00145 protected:
00146 double cost_;
00147 double sort_value_;
00148 StatePtr state_;
00149 Ptr parent_;
00150 GraphWeakPtr graph_;
00151
00152 private:
00153
00154 };
00155
00156
00157 }
00158
00159 #endif