ProductGraph.h
162 std::vector<State*> computeLead(State* start, const boost::function<double(State*, State*)>& edgeWeight);
172 void buildGraph(State* start, const boost::function<void(State*)>& initialize = ProductGraph::noInit);
240 typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS, State*, Edge> GraphType;
double getRegionVolume(const State *s)
Helper method to return the volume of the PropositionalDecomposition region corresponding to the give...
Definition: ProductGraph.cpp:261
const AutomatonPtr & getSafetyAutom() const
Returns the safe Automaton contained within this ProductGraph.
Definition: ProductGraph.cpp:101
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
const AutomatonPtr & getCosafetyAutom() const
Returns the co-safe Automaton contained within this ProductGraph.
Definition: ProductGraph.cpp:96
const PropositionalDecompositionPtr & getDecomp() const
Returns the PropositionalDecomposition contained within this ProductGraph.
Definition: ProductGraph.cpp:91
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::PropositionalDecomposition.
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
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
int getCosafeState(void) const
Returns this State's co-safe Automaton state component.
Definition: ProductGraph.cpp:60
int getDecompRegion(void) const
Returns this State's PropositionalDecomposition region component.
Definition: ProductGraph.cpp:55
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
A ProductGraph represents the weighted, directed, graph-based Cartesian product of a PropositionalDec...
Definition: ProductGraph.h:67
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
State * getState(int region, int cosafe, int safe) const
Returns the ProductGraph state corresponding to the given region, co-safety state, and safety state.
Definition: ProductGraph.h:220
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
A State of a ProductGraph represents a vertex in the graph-based Cartesian product represented by the...
Definition: ProductGraph.h:74
State(void)
Creates a State without any assigned PropositionalDecomposition region or Automaton states...
Definition: ProductGraph.h:80
State * getStartState(void) const
Returns the initial State of this ProductGraph.
Definition: ProductGraph.cpp:256
A boost shared pointer wrapper for ompl::control::Automaton.
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
int getSafeState(void) const
Returns this State's safe Automaton state component.
Definition: ProductGraph.cpp:65
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