ProductGraph.cpp
91 const ompl::control::PropositionalDecompositionPtr& ompl::control::ProductGraph::getDecomp() const
132 for (std::vector<State*>::const_iterator s = solutionStates_.begin()+1; s != solutionStates_.end(); ++s)
175 void ompl::control::ProductGraph::buildGraph(State* start, const boost::function<void(State*)>& initialize)
233 boost::tie(edge,ignore) = boost::add_edge(v, boost::vertex(stateToIndex_[nextState],graph_), graph_);
247 OMPL_INFORM("Number of high-level states in abstraction graph: %u", boost::num_vertices(graph_));
276 ompl::control::ProductGraph::State* ompl::control::ProductGraph::getState(const base::State* cs) const
281 ompl::control::ProductGraph::State* ompl::control::ProductGraph::getState(const base::State* cs, int cosafe, int safe) const
293 ompl::control::ProductGraph::State* ompl::control::ProductGraph::getState(const State* parent, int nextRegion) const
306 ompl::control::ProductGraph::State* ompl::control::ProductGraph::getState(const State* parent, const base::State* cs) const
double getRegionVolume(const State *s)
Helper method to return the volume of the PropositionalDecomposition region corresponding to the give...
Definition: ProductGraph.cpp:261
A class to represent an assignment of boolean values to propositions. A World can be partially restri...
Definition: World.h:51
A boost shared pointer wrapper for ompl::control::PropositionalDecomposition.
void buildGraph(State *start, const boost::function< void(State *)> &initialize=ProductGraph::noInit)
Constructs this ProductGraph beginning with a given initial State, using a breadth-first search...
Definition: ProductGraph.cpp:175
State * getState(const base::State *cs) const
Returns a ProductGraph State with initial co-safety and safety Automaton states, and the Propositiona...
Definition: ProductGraph.cpp:276
int getSafeAutDistance(const State *s) const
Helper method to return the distance from a given State's safety state to an accepting state in the s...
Definition: ProductGraph.cpp:271
State * getStartState(void) const
Returns the initial State of this ProductGraph.
Definition: ProductGraph.cpp:256
std::vector< State * > computeLead(State *start, const boost::function< double(State *, State *)> &edgeWeight)
Returns a shortest-path sequence of ProductGraph states, beginning with a given initial State and end...
Definition: ProductGraph.cpp:107
const PropositionalDecompositionPtr & getDecomp() const
Returns the PropositionalDecomposition contained within this ProductGraph.
Definition: ProductGraph.cpp:91
int getCosafeAutDistance(const State *s) const
Helper method to return the distance from a given State's co-safety state to an accepting state in th...
Definition: ProductGraph.cpp:266
const AutomatonPtr & getSafetyAutom() const
Returns the safe Automaton contained within this ProductGraph.
Definition: ProductGraph.cpp:101
A State of a ProductGraph represents a vertex in the graph-based Cartesian product represented by the...
Definition: ProductGraph.h:74
bool isValid(void) const
Returns whether this State is valid. A State is valid if and only if none of its Automaton states are...
Definition: ProductGraph.cpp:28
int getSafeState(void) const
Returns this State's safe Automaton state component.
Definition: ProductGraph.cpp:65
bool operator==(const State &s) const
Returns whether this State is equivalent to a given State, by comparing their PropositionalDecomposit...
Definition: ProductGraph.cpp:21
A boost shared pointer wrapper for ompl::control::Automaton.
bool isSolution(const State *s) const
Returns whether the given State is an accepting State in this ProductGraph. We call a State accepting...
Definition: ProductGraph.cpp:250
int getDecompRegion(void) const
Returns this State's PropositionalDecomposition region component.
Definition: ProductGraph.cpp:55
A class to represent a deterministic finite automaton, each edge of which corresponds to a World...
Definition: Automaton.h:69
int getCosafeState(void) const
Returns this State's co-safe Automaton state component.
Definition: ProductGraph.cpp:60
friend std::ostream & operator<<(std::ostream &out, const State &s)
Helper function to print this State to a given output stream.
Definition: ProductGraph.cpp:46
ProductGraph(const PropositionalDecompositionPtr &decomp, const AutomatonPtr &cosafetyAut, const AutomatonPtr &safetyAut)
Initializes a ProductGraph with a given PropositionalDecomposition, co-safe Automaton, and safe Automaton.
Definition: ProductGraph.cpp:70
const AutomatonPtr & getCosafetyAutom() const
Returns the co-safe Automaton contained within this ProductGraph.
Definition: ProductGraph.cpp:96