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/function.hpp>
45 #include <boost/graph/adjacency_list.hpp>
46 #include <boost/unordered_map.hpp>
47 #include <map>
48 #include <ostream>
49 #include <vector>
50 
51 namespace ompl
52 {
53  namespace control
54  {
56 
57  OMPL_CLASS_FORWARD(ProductGraph);
59 
68  {
69  public:
74  class State
75  {
76  friend class ProductGraph;
77  public:
80  State(void)
81  : decompRegion(-1),
82  cosafeState(-1),
83  safeState(-1) { }
84 
86  State(const State& s)
87  : decompRegion(s.decompRegion),
88  cosafeState(s.cosafeState),
89  safeState(s.safeState) { }
90 
94  bool operator==(const State& s) const;
95 
99  bool isValid(void) const;
100 
102 
103  friend std::size_t hash_value(const ProductGraph::State& s);
105 
107  friend std::ostream& operator<<(std::ostream& out, const State& s);
108 
110  int getDecompRegion(void) const;
111 
113  int getCosafeState(void) const;
114 
116  int getSafeState(void) const;
117 
118  private:
119  int decompRegion;
120  int cosafeState;
121  int safeState;
122  };
123 
126  ProductGraph(
127  const PropositionalDecompositionPtr& decomp,
128  const AutomatonPtr& cosafetyAut,
129  const AutomatonPtr& safetyAut
130  );
131 
135  ProductGraph(
136  const PropositionalDecompositionPtr& decomp,
137  const AutomatonPtr& cosafetyAut
138  );
139 
140  ~ProductGraph();
141 
145 
148  const AutomatonPtr& getCosafetyAutom() const;
149 
152  const AutomatonPtr& getSafetyAutom() const;
153 
162  std::vector<State*> computeLead(State* start, const boost::function<double(State*, State*)>& edgeWeight);
163 
165  void clear();
166 
172  void buildGraph(State* start, const boost::function<void(State*)>& initialize = ProductGraph::noInit);
173 
180  bool isSolution(const State* s) const;
181 
183  State* getStartState(void) const;
184 
187  double getRegionVolume(const State* s);
188 
191  int getCosafeAutDistance(const State* s) const;
192 
195  int getSafeAutDistance(const State* s) const;
196 
200  State* getState(const base::State* cs) const;
201 
205  State* getState(const base::State* cs, int cosafe, int safe) const;
206 
210  State* getState(const State* parent, int nextRegion) const;
211 
216  State* getState(const State* parent, const base::State* cs) const;
217 
220  State* getState(int region, int cosafe, int safe) const
221  {
222  State s;
223  s.decompRegion = region;
224  s.cosafeState = cosafe;
225  s.safeState = safe;
226  State*& ret = stateToPtr_[s];
227  if (ret == NULL) ret = new State(s);
228  return ret;
229  }
230 
231  protected:
232  static void noInit(State* s)
233  {
234  }
235  struct Edge
236  {
237  double cost;
238  };
239 
240  typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS, State*, Edge> GraphType;
241  typedef boost::graph_traits<GraphType>::vertex_descriptor Vertex;
242  typedef boost::graph_traits<GraphType>::vertex_iterator VertexIter;
243  typedef boost::property_map<GraphType, boost::vertex_index_t>::type VertexIndexMap;
244  typedef boost::graph_traits<GraphType>::edge_iterator EdgeIter;
245 
247  AutomatonPtr cosafety_;
248  AutomatonPtr safety_;
249  GraphType graph_;
250  State* startState_;
251  std::vector<State*> solutionStates_;
252 
253  /* Only one State pointer will be allocated for each possible State
254  in the ProductGraph. There will exist situations in which
255  all we have are the component values (region, automaton states)
256  of a State and we want the actual State pointer.
257  We use this map to access it. */
258  mutable boost::unordered_map<State, State*> stateToPtr_;
259 
260  /* Map from State pointer to the index of the corresponding vertex
261  in the graph. */
262  boost::unordered_map<State*, int> stateToIndex_;
263  };
264  }
265 }
266 #endif
double getRegionVolume(const State *s)
Helper method to return the volume of the PropositionalDecomposition region corresponding to the give...
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...
State * getState(const base::State *cs) const
Returns a ProductGraph State with initial co-safety and safety Automaton states, and the Propositiona...
A ProductGraph represents the weighted, directed, graph-based Cartesian product of a PropositionalDec...
Definition: ProductGraph.h:67
int getSafeAutDistance(const State *s) const
Helper method to return the distance from a given State&#39;s safety state to an accepting state in the s...
State * getStartState(void) const
Returns the initial State of this ProductGraph.
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...
Main namespace. Contains everything in this library.
Definition: Cost.h:42
const PropositionalDecompositionPtr & getDecomp() const
Returns the PropositionalDecomposition contained within this ProductGraph.
int getCosafeAutDistance(const State *s) const
Helper method to return the distance from a given State&#39;s co-safety state to an accepting state in th...
const AutomatonPtr & getSafetyAutom() const
Returns the safe Automaton contained within this ProductGraph.
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
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 of an abstract state.
Definition: State.h:50
void clear()
Clears all memory belonging to this ProductGraph.
State(const State &s)
Basic copy constructor for State.
Definition: ProductGraph.h:86
int getSafeState(void) const
Returns this State&#39;s safe Automaton state component.
bool operator==(const State &s) const
Returns whether this State is equivalent to a given State, by comparing their PropositionalDecomposit...
A boost shared pointer wrapper for ompl::control::Automaton.
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 isSolution(const State *s) const
Returns whether the given State is an accepting State in this ProductGraph. We call a State accepting...
int getDecompRegion(void) const
Returns this State&#39;s PropositionalDecomposition region component.
int getCosafeState(void) const
Returns this State&#39;s co-safe Automaton state component.
friend std::ostream & operator<<(std::ostream &out, const State &s)
Helper function to print this State to a given output stream.
const AutomatonPtr & getCosafetyAutom() const
Returns the co-safe Automaton contained within this ProductGraph.