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 
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() : decompRegion(-1), cosafeState(-1), safeState(-1)
91  {
92  }
93 
95  State(const State &s) = default;
96 
100  bool operator==(const State &s) const;
101 
105  bool isValid() const;
106 
107  friend struct HashState;
108 
110  friend std::ostream &operator<<(std::ostream &out, const State &s);
111 
113  int getDecompRegion() const;
114 
116  int getCosafeState() const;
117 
119  int getSafeState() const;
120 
121  private:
122  int decompRegion;
123  int cosafeState;
124  int safeState;
125  };
126 
130 
134  ProductGraph(const PropositionalDecompositionPtr &decomp, AutomatonPtr cosafetyAut);
135 
136  ~ProductGraph();
137 
141 
144  const AutomatonPtr &getCosafetyAutom() const;
145 
148  const AutomatonPtr &getSafetyAutom() const;
149 
158  std::vector<State *> computeLead(State *start, const std::function<double(State *, State *)> &edgeWeight);
159 
161  void clear();
162 
168  void buildGraph(State *start, const std::function<void(State *)> &initialize = ProductGraph::noInit);
169 
176  bool isSolution(const State *s) const;
177 
179  State *getStartState() const;
180 
183  double getRegionVolume(const State *s);
184 
187  int getCosafeAutDistance(const State *s) const;
188 
191  int getSafeAutDistance(const State *s) const;
192 
196  State *getState(const base::State *cs) const;
197 
201  State *getState(const base::State *cs, int cosafe, int safe) const;
202 
206  State *getState(const State *parent, int nextRegion) const;
207 
212  State *getState(const State *parent, const base::State *cs) const;
213 
216  State *getState(int region, int cosafe, int safe) const
217  {
218  State s;
219  s.decompRegion = region;
220  s.cosafeState = cosafe;
221  s.safeState = safe;
222  State *&ret = stateToPtr_[s];
223  if (ret == nullptr)
224  ret = new State(s);
225  return ret;
226  }
227 
228  protected:
229  static void noInit(State *s)
230  {
231  }
232  struct Edge
233  {
234  double cost;
235  };
236 
237  using GraphType = boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS, State *, Edge>;
238  using Vertex = boost::graph_traits<GraphType>::vertex_descriptor;
239  using VertexIter = boost::graph_traits<GraphType>::vertex_iterator;
240  using VertexIndexMap = boost::property_map<GraphType, boost::vertex_index_t>::type;
241  using EdgeIter = boost::graph_traits<GraphType>::edge_iterator;
242 
244  AutomatonPtr cosafety_;
245  AutomatonPtr safety_;
246  GraphType graph_;
247  State *startState_;
248  std::vector<State *> solutionStates_;
249 
250  /* Only one State pointer will be allocated for each possible State
251  in the ProductGraph. There will exist situations in which
252  all we have are the component values (region, automaton states)
253  of a State and we want the actual State pointer.
254  We use this map to access it. */
255  mutable std::unordered_map<State, State *, HashState> stateToPtr_;
256 
257  /* Map from State pointer to the index of the corresponding vertex
258  in the graph. */
259  std::unordered_map<State *, int> stateToIndex_;
260  };
261  }
262 }
263 #endif
double getRegionVolume(const State *s)
Helper method to return the volume of the PropositionalDecomposition region corresponding to the give...
const AutomatonPtr & getSafetyAutom() const
Returns the safe Automaton contained within this ProductGraph.
bool isSolution(const State *s) const
Returns whether the given State is an accepting State in this ProductGraph. We call a State accepting...
const AutomatonPtr & getCosafetyAutom() const
Returns the co-safe Automaton contained within this ProductGraph.
const PropositionalDecompositionPtr & getDecomp() const
Returns the PropositionalDecomposition contained within this ProductGraph.
A shared pointer wrapper for ompl::control::PropositionalDecomposition.
State()
Creates a State without any assigned PropositionalDecomposition region or Automaton states...
Definition: ProductGraph.h:90
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 * 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:66
std::ostream & operator<<(std::ostream &out, const ScopedState< T > &state)
Overload stream output operator. Calls ompl::base::StateSpace::printState()
Definition: ScopedState.h:493
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
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:216
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...
A State of a ProductGraph represents a vertex in the graph-based Cartesian product represented by the...
Definition: ProductGraph.h:83
Definition of an abstract state.
Definition: State.h:49
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::Automaton.
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...
ProductGraph(PropositionalDecompositionPtr decomp, AutomatonPtr cosafetyAut, AutomatonPtr safetyAut)
Initializes a ProductGraph with a given PropositionalDecomposition, co-safe Automaton, and safe Automaton.
void buildGraph(State *start, const std::function< void(State *)> &initialize=ProductGraph::noInit)
Constructs this ProductGraph beginning with a given initial State, using a breadth-first search...