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
00059 SolverNode(StatePtr state, const double cost,
00060 Ptr parent, GraphPtr graph):
00061 cost_(cost), state_(state), parent_(parent), graph_(graph) {}
00062
00063 SolverNode(StatePtr state, const double cost, GraphPtr graph):
00064 cost_(cost), state_(state), graph_(graph) {}
00065
00066 virtual
00067 StatePtr getState() const { return state_; }
00068
00069 virtual
00070 std::vector<Ptr> wrapWithSolverNodes(Ptr this_ptr, std::vector<StatePtr> successors)
00071 {
00072 GraphPtr graph_ptr = graph_.lock();
00073 std::vector<Ptr> solver_nodes;
00074 for (size_t i = 0; i < successors.size(); i++) {
00075 StatePtr next_state = successors[i];
00076 SolverNode::Ptr solver_node(new SolverNode(
00077 next_state,
00078 graph_ptr->pathCost(state_, next_state, cost_),
00079 this_ptr,
00080 graph_ptr));
00081 solver_nodes.push_back(solver_node);
00082 }
00083 return solver_nodes;
00084 }
00085
00086 virtual
00087 std::vector<Ptr> expand(Ptr this_ptr, bool verbose)
00088 {
00089 GraphPtr graph_ptr = graph_.lock();
00090 std::vector<Ptr> solver_nodes;
00091 if (graph_ptr) {
00092 std::vector<StatePtr> successors = graph_ptr->successors(state_);
00093 if (verbose) {
00094 std::cerr << successors.size() << " successors" << std::endl;
00095 }
00096 return wrapWithSolverNodes(this_ptr, successors);
00097 }
00098 else {
00099
00100
00101 throw std::runtime_error("no graph is set in SolverNode");
00102 }
00103 return solver_nodes;
00104 }
00105
00106 bool isRoot() const { return !parent_; }
00107 double getCost() const { return cost_; }
00108 double getSortValue() const { return sort_value_; }
00109 void setGraph(GraphPtr graph) { graph_ = graph; }
00110 void setSortValue(double v) { sort_value_ = v; }
00111 void setCost(double c) { cost_ = c; }
00112
00113 std::vector<SolverNode::Ptr>
00114 getPathWithoutThis()
00115 {
00116 if (isRoot()) {
00117 return std::vector<SolverNode::Ptr>();
00118 }
00119 else {
00120 std::vector<SolverNode::Ptr> parent_path = parent_->getPathWithoutThis();
00121 parent_path.push_back(parent_);
00122 return parent_path;
00123 }
00124 }
00125
00126 virtual void setState(StatePtr state) { state_ = state; }
00127
00128 friend bool operator<(const SolverNode<StateT, GraphT>::Ptr a,
00129 const SolverNode<StateT, GraphT>::Ptr b)
00130 {
00131 return a->getSortValue() < b->getSortValue();
00132 }
00133
00134 friend bool operator>(const SolverNode<StateT, GraphT>::Ptr a,
00135 const SolverNode<StateT, GraphT>::Ptr b)
00136 {
00137 return a->getSortValue() > b->getSortValue();
00138 }
00139
00140 virtual Ptr getParent() const { return parent_; }
00141
00142 protected:
00143 double cost_;
00144 double sort_value_;
00145 StatePtr state_;
00146 Ptr parent_;
00147 GraphWeakPtr graph_;
00148
00149 private:
00150 };
00151
00152 #if 0 // Not using, but for testing
00153 template <class StateT, class GraphT>
00154 class SolverNodeSingleton : public SolverNode< StateT, GraphT >
00155 {
00156 public:
00157 typedef boost::shared_ptr<SolverNodeSingleton> SPtr;
00158 typedef boost::shared_ptr< SolverNode< StateT, GraphT > > Ptr;
00159 typedef boost::shared_ptr<StateT> StatePtr;
00160 typedef typename GraphT::Ptr GraphPtr;
00161 typedef typename boost::weak_ptr<GraphT> GraphWeakPtr;
00162
00163 using SolverNode< StateT, GraphT >::isRoot;
00164
00165 SolverNodeSingleton(StatePtr state, const double cost,
00166 Ptr parent, GraphPtr graph) :
00167 SolverNode< StateT, GraphT > (state, cost, parent, graph) {}
00168
00169 SolverNodeSingleton(StatePtr state, const double cost, GraphPtr graph) :
00170 SolverNode< StateT, GraphT >(state, cost, graph) {}
00171
00172 virtual
00173 std::vector<Ptr> wrapWithSolverNodes(Ptr this_ptr, std::vector<StatePtr> successors)
00174 {
00175 GraphPtr graph_ptr = graph_.lock();
00176 std::vector<Ptr> solver_nodes;
00177 for (size_t i = 0; i < successors.size(); i++) {
00178 StatePtr next_state = successors[i];
00179 Ptr solver_node(new SolverNodeSingleton(
00180 next_state,
00181 graph_ptr->pathCost(state_, next_state, cost_),
00182 this_ptr,
00183 graph_ptr));
00184 solver_nodes.push_back(solver_node);
00185 }
00186 return solver_nodes;
00187 }
00188
00189 std::vector<Ptr>
00190 getPathWithoutThis()
00191 {
00192 if (isRoot()) {
00193 return std::vector<Ptr>();
00194 }
00195 else {
00196 std::vector<Ptr> parent_path = parent_->getPathWithoutThis();
00197 parent_path.push_back(graph_->getNode(parent_));
00198 return parent_path;
00199 }
00200 }
00201 protected:
00202 using SolverNode< StateT, GraphT >::cost_;
00203 using SolverNode< StateT, GraphT >::sort_value_;
00204 using SolverNode< StateT, GraphT >::state_;
00205 using SolverNode< StateT, GraphT >::parent_;
00206 using SolverNode< StateT, GraphT >::graph_;
00207 private:
00208 };
00209 #endif
00210 }
00211
00212 #endif