Class ProductGraph

Nested Relationships

Nested Types

Class Documentation

class ProductGraph

A ProductGraph represents the weighted, directed, graph-based Cartesian product of a PropositionalDecomposition object, an Automaton corresponding to a co-safe LTL specification, and an Automaton corresponding to a safe LTL specification.

Public Functions

ProductGraph(PropositionalDecompositionPtr decomp, AutomatonPtr cosafetyAut, AutomatonPtr safetyAut)

Initializes a ProductGraph with a given PropositionalDecomposition, co-safe Automaton, and safe Automaton.

ProductGraph(const PropositionalDecompositionPtr &decomp, AutomatonPtr cosafetyAut)

Initializes an abstraction with a given propositional decomposition and cosafety automaton. The safety automaton is set to be one that always accepts.

~ProductGraph()
const PropositionalDecompositionPtr &getDecomp() const

Returns the PropositionalDecomposition contained within this ProductGraph.

const AutomatonPtr &getCosafetyAutom() const

Returns the co-safe Automaton contained within this ProductGraph.

const AutomatonPtr &getSafetyAutom() const

Returns the safe Automaton contained within this ProductGraph.

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 ending with a State for which the corresponding safety Automaton state is accepting, and the corresponding co-safety Automaton state is as close as possible to an accepting state given the adjacency properties of the PropositionalDecomposition. Dijkstra’s shortest-path algorithm is used to compute the path with the given edge-weight function.

void clear()

Clears all memory belonging to this ProductGraph.

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. Accepts an optional initialization method, which will be called exactly once on each State (including the given initial State) that is added to the ProductGraph. The default argument for the initialization method is a no-op method.

bool isSolution(const State *s) const

Returns whether the given State is an accepting State in this ProductGraph. We call a State accepting if its safety Automaton state component is accepting, and its co-safety Automaton state component is as close as possible to an accepting state in the co-safety Automaton given the adjacency properties of the PropositionalDecomposition.

State *getStartState() const

Returns the initial State of this ProductGraph.

double getRegionVolume(const State *s)

Helper method to return the volume of the PropositionalDecomposition region corresponding to the given ProductGraph State.

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 the co-safety Automaton.

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 safety Automaton.

State *getState(const base::State *cs) const

Returns a ProductGraph State with initial co-safety and safety Automaton states, and the PropositionalDecomposition region that contains a given base::State.

State *getState(const base::State *cs, int cosafe, int safe) const

Returns a ProductGraph State with given co-safety and safety Automaton states, and the PropositionalDecomposition region that contains a given base::State.

State *getState(const State *parent, int nextRegion) const

Returns a ProductGraph State with a given PropositionalDecomposition region. The co-safety and safety Automaton states are calculated using a given parent ProductGraph State and the decomposition region.

State *getState(const State *parent, const base::State *cs) const

Returns a ProductGraph state with the PropositionalDecomposition region that contains a given base::State. The co-safety and safety Automaton states are calculated using a given parent ProductGraph State and the decomposition region.

inline State *getState(int region, int cosafe, int safe) const

Returns the ProductGraph state corresponding to the given region, co-safety state, and safety state.

Protected Types

using GraphType = boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS, State*, Edge>
using Vertex = boost::graph_traits<GraphType>::vertex_descriptor
using VertexIter = boost::graph_traits<GraphType>::vertex_iterator
using VertexIndexMap = boost::property_map<GraphType, boost::vertex_index_t>::type
using EdgeIter = boost::graph_traits<GraphType>::edge_iterator

Protected Attributes

PropositionalDecompositionPtr decomp_
AutomatonPtr cosafety_
AutomatonPtr safety_
GraphType graph_
State *startState_
std::vector<State*> solutionStates_
mutable std::unordered_map<State, State*, HashState> stateToPtr_
std::unordered_map<State*, int> stateToIndex_
struct Edge

Public Members

double cost = {0}
class State

A State of a ProductGraph represents a vertex in the graph-based Cartesian product represented by the ProductGraph. A State is simply a tuple consisting of a PropositionalDecomposition region, a co-safe Automaton state, and a safe Automaton state.

Public Functions

State() = default

Creates a State without any assigned PropositionalDecomposition region or Automaton states. All of these values are initialized to -1.

State(const State &s) = default

Basic copy constructor for State.

bool operator==(const State &s) const

Returns whether this State is equivalent to a given State, by comparing their PropositionalDecomposition regions and Automaton states.

bool isValid() const

Returns whether this State is valid. A State is valid if and only if none of its Automaton states are dead states (a dead state has value -1).

int getDecompRegion() const

Returns this State’s PropositionalDecomposition region component.

int getCosafeState() const

Returns this State’s co-safe Automaton state component.

int getSafeState() const

Returns this State’s safe Automaton state component.

Friends

friend struct HashState
friend std::ostream &operator<<(std::ostream &out, const State &s)

Helper function to print this State to a given output stream.