ProductGraph.cpp
60 return decompRegion == s.decompRegion && cosafeState == s.cosafeState && safeState == s.safeState;
68 std::size_t ompl::control::ProductGraph::HashState::operator()(const ompl::control::ProductGraph::State &s) const
104 ompl::control::ProductGraph::ProductGraph(PropositionalDecompositionPtr decomp, AutomatonPtr cosafetyAut,
110 ompl::control::ProductGraph::ProductGraph(const PropositionalDecompositionPtr &decomp, AutomatonPtr cosafetyAut)
111 : decomp_(decomp), cosafety_(std::move(cosafetyAut)), safety_(Automaton::AcceptingAutomaton(decomp->getNumProps()))
120 const ompl::control::PropositionalDecompositionPtr &ompl::control::ProductGraph::getDecomp() const
136 ProductGraph::State *start, const std::function<double(ProductGraph::State *, ProductGraph::State *)> &edgeWeight)
154 .distance_map(boost::make_iterator_property_map(distances.begin(), get(boost::vertex_index, graph_)))
155 .predecessor_map(boost::make_iterator_property_map(parents.begin(), get(boost::vertex_index, graph_))));
159 for (std::vector<State *>::const_iterator s = solutionStates_.begin() + 1; s != solutionStates_.end(); ++s)
201 void ompl::control::ProductGraph::buildGraph(State *start, const std::function<void(State *)> &initialize)
217 OMPL_INFORM("Building graph from start state (%u,%u,%u) with index %d", startState_->decompRegion,
258 boost::tie(edge, ignore) = boost::add_edge(v, boost::vertex(stateToIndex_[nextState], graph_), graph_);
272 OMPL_INFORM("Number of high-level states in abstraction graph: %u", boost::num_vertices(graph_));
300 ompl::control::ProductGraph::State *ompl::control::ProductGraph::getState(const base::State *cs) const
305 ompl::control::ProductGraph::State *ompl::control::ProductGraph::getState(const base::State *cs, int cosafe,
318 ompl::control::ProductGraph::State *ompl::control::ProductGraph::getState(const State *parent, int nextRegion) const
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:275
bool isValid() const
Returns whether this State is valid. A State is valid if and only if none of its Automaton states are...
Definition: ProductGraph.cpp:63
const AutomatonPtr & getCosafetyAutom() const
Returns the co-safe Automaton contained within this ProductGraph.
Definition: ProductGraph.cpp:125
const PropositionalDecompositionPtr & getDecomp() const
Returns the PropositionalDecomposition contained within this ProductGraph.
Definition: ProductGraph.cpp:120
bool operator==(const State &s) const
Returns whether this State is equivalent to a given State, by comparing their PropositionalDecomposit...
Definition: ProductGraph.cpp:58
int getDecompRegion() const
Returns this State's PropositionalDecomposition region component.
Definition: ProductGraph.cpp:89
int getSafeState() const
Returns this State's safe Automaton state component.
Definition: ProductGraph.cpp:99
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:290
std::vector< State * > computeLead(State *start, const std::function< double(State *, State *)> &edgeWeight)
Returns a shortest-path sequence of ProductGraph states, beginning with a given initial State and end...
Definition: ProductGraph.cpp:135
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:300
A State of a ProductGraph represents a vertex in the graph-based Cartesian product represented by the...
Definition: ProductGraph.h:147
A shared pointer wrapper for ompl::control::Automaton.
ProductGraph(PropositionalDecompositionPtr decomp, AutomatonPtr cosafetyAut, AutomatonPtr safetyAut)
Initializes a ProductGraph with a given PropositionalDecomposition, co-safe Automaton,...
Definition: ProductGraph.cpp:104
State * getStartState() const
Returns the initial State of this ProductGraph.
Definition: ProductGraph.cpp:280
A class to represent a deterministic finite automaton, each edge of which corresponds to a World....
Definition: Automaton.h:134
A shared pointer wrapper for ompl::control::PropositionalDecomposition.
int getCosafeState() const
Returns this State's co-safe Automaton state component.
Definition: ProductGraph.cpp:94
const AutomatonPtr & getSafetyAutom() const
Returns the safe Automaton contained within this ProductGraph.
Definition: ProductGraph.cpp:130
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:295
double getRegionVolume(const State *s)
Helper method to return the volume of the PropositionalDecomposition region corresponding to the give...
Definition: ProductGraph.cpp:285
Main namespace. Contains everything in this library.
Definition: MultiLevelPlanarManipulatorDemo.cpp:65
void buildGraph(State *start, const std::function< void(State *)> &initialize=[](State *){})
Constructs this ProductGraph beginning with a given initial State, using a breadth-first search....
Definition: ProductGraph.cpp:201
A class to represent an assignment of boolean values to propositions. A World can be partially restri...
Definition: World.h:71