ProductGraph.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Rice University
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Rice University nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Matt Maly */
36 
37 #ifndef OMPL_CONTROL_PLANNERS_LTL_PRODUCTGRAPH_
38 #define OMPL_CONTROL_PLANNERS_LTL_PRODUCTGRAPH_
39 
40 #include "ompl/base/State.h"
41 #include "ompl/control/planners/ltl/Automaton.h"
42 #include "ompl/control/planners/ltl/PropositionalDecomposition.h"
43 #include "ompl/util/ClassForward.h"
44 #include <boost/graph/adjacency_list.hpp>
45 #include <unordered_map>
46 #include <map>
47 #include <ostream>
48 #include <vector>
49 
50 namespace ompl
51 {
52  namespace control
53  {
55 
56  OMPL_CLASS_FORWARD(ProductGraph);
58 
66  class ProductGraph
67  {
68  public:
69  class State;
70 
72 
73  struct HashState
74  {
75  std::size_t operator()(const State &s) const;
76  };
78 
83  class State
84  {
85  friend class ProductGraph;
86 
87  public:
90  State() = default;
91 
93  State(const State &s) = default;
94 
98  bool operator==(const State &s) const;
99 
103  bool isValid() const;
104 
105  friend struct HashState;
106 
108  friend std::ostream &operator<<(std::ostream &out, const State &s);
109 
111  int getDecompRegion() const;
112 
114  int getCosafeState() const;
115 
117  int getSafeState() const;
118 
119  private:
120  int decompRegion{-1};
121  int cosafeState{-1};
122  int safeState{-1};
123  };
124 
128 
132  ProductGraph(const PropositionalDecompositionPtr &decomp, AutomatonPtr cosafetyAut);
133 
134  ~ProductGraph();
135 
139 
142  const AutomatonPtr &getCosafetyAutom() const;
143 
146  const AutomatonPtr &getSafetyAutom() const;
147 
156  std::vector<State *> computeLead(State *start, const std::function<double(State *, State *)> &edgeWeight);
157 
159  void clear();
160 
166  void buildGraph(State *start, const std::function<void(State *)> &initialize = [](State *){});
167 
174  bool isSolution(const State *s) const;
175 
177  State *getStartState() const;
178 
181  double getRegionVolume(const State *s);
182 
185  int getCosafeAutDistance(const State *s) const;
186 
189  int getSafeAutDistance(const State *s) const;
190 
194  State *getState(const base::State *cs) const;
195 
199  State *getState(const base::State *cs, int cosafe, int safe) const;
200 
204  State *getState(const State *parent, int nextRegion) const;
205 
210  State *getState(const State *parent, const base::State *cs) const;
211 
214  State *getState(int region, int cosafe, int safe) const
215  {
216  State s;
217  s.decompRegion = region;
218  s.cosafeState = cosafe;
219  s.safeState = safe;
220  State *&ret = stateToPtr_[s];
221  if (ret == nullptr)
222  ret = new State(s);
223  return ret;
224  }
225 
226  protected:
227  struct Edge
228  {
229  double cost;
230  };
231 
232  using GraphType = boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS, State *, Edge>;
233  using Vertex = boost::graph_traits<GraphType>::vertex_descriptor;
234  using VertexIter = boost::graph_traits<GraphType>::vertex_iterator;
235  using VertexIndexMap = boost::property_map<GraphType, boost::vertex_index_t>::type;
236  using EdgeIter = boost::graph_traits<GraphType>::edge_iterator;
237 
239  AutomatonPtr cosafety_;
240  AutomatonPtr safety_;
241  GraphType graph_;
242  State *startState_;
243  std::vector<State *> solutionStates_;
244 
245  /* Only one State pointer will be allocated for each possible State
246  in the ProductGraph. There will exist situations in which
247  all we have are the component values (region, automaton states)
248  of a State and we want the actual State pointer.
249  We use this map to access it. */
250  mutable std::unordered_map<State, State *, HashState> stateToPtr_;
251 
252  /* Map from State pointer to the index of the corresponding vertex
253  in the graph. */
254  std::unordered_map<State *, int> stateToIndex_;
255  };
256  }
257 }
258 #endif
bool isSolution(const State *s) const
Returns whether the given State is an accepting State in this ProductGraph. We call a State accepting...
bool isValid() const
Returns whether this State is valid. A State is valid if and only if none of its Automaton states are...
const AutomatonPtr & getCosafetyAutom() const
Returns the co-safe Automaton contained within this ProductGraph.
const PropositionalDecompositionPtr & getDecomp() const
Returns the PropositionalDecomposition contained within this ProductGraph.
bool operator==(const State &s) const
Returns whether this State is equivalent to a given State, by comparing their PropositionalDecomposit...
int getDecompRegion() const
Returns this State's PropositionalDecomposition region component.
int getSafeState() const
Returns this State's safe Automaton state component.
Definition of an abstract state.
Definition: State.h:113
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...
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...
State * getState(const base::State *cs) const
Returns a ProductGraph State with initial co-safety and safety Automaton states, and the Propositiona...
State()=default
Creates a State without any assigned PropositionalDecomposition region or Automaton states....
A State of a ProductGraph represents a vertex in the graph-based Cartesian product represented by the...
Definition: ProductGraph.h:147
friend std::ostream & operator<<(std::ostream &out, const State &s)
Helper function to print this State to a given output stream.
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,...
State * getStartState() const
Returns the initial State of this ProductGraph.
void clear()
Clears all memory belonging to this ProductGraph.
A shared pointer wrapper for ompl::control::PropositionalDecomposition.
int getCosafeState() const
Returns this State's co-safe Automaton state component.
const AutomatonPtr & getSafetyAutom() const
Returns the safe Automaton contained within this ProductGraph.
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...
double getRegionVolume(const State *s)
Helper method to return the volume of the PropositionalDecomposition region corresponding to the give...
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
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....