LTLPlanner.cpp
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 #include "ompl/control/planners/ltl/LTLPlanner.h"
38 #include "ompl/control/planners/PlannerIncludes.h"
39 #include "ompl/control/planners/ltl/ProductGraph.h"
40 #include "ompl/control/planners/ltl/LTLProblemDefinition.h"
41 #include "ompl/datastructures/PDF.h"
42 #include "ompl/util/Console.h"
43 #include <algorithm>
44 #include <unordered_map>
45 #include <limits>
46 #include <map>
47 #include <utility>
48 #include <vector>
49 
50 #include <cstdio>
51 
53  : ompl::base::Planner(ltlsi, "LTLPlanner")
54  , ltlsi_(ltlsi.get())
55  , abstraction_(std::move(a))
56  , exploreTime_(exploreTime)
57 {
59 }
60 
62 {
63  clearMotions();
64 }
65 
67 {
69 }
70 
72 {
74  availDist_.clear();
75  abstractInfo_.clear();
76  clearMotions();
77 }
78 
80 {
81  // \todo make solve work when called more than once!
82  checkValidity();
83  const base::State *start = pis_.nextStart();
84  prodStart_ = ltlsi_->getProdGraphState(start);
85 
87  OMPL_WARN("Multiple start states given. Using only the first start state.");
88 
89  auto *startMotion = new Motion(ltlsi_);
90  si_->copyState(startMotion->state, start);
91  ltlsi_->nullControl(startMotion->control);
92  startMotion->abstractState = prodStart_;
93 
94  motions_.push_back(startMotion);
95  abstractInfo_[prodStart_].addMotion(startMotion);
98 
99  abstraction_->buildGraph(prodStart_, [this](ProductGraph::State *as)
100  {
101  initAbstractInfo(as);
102  });
103 
104  if (!sampler_)
105  sampler_ = si_->allocStateSampler();
106  if (!controlSampler_)
108 
109  bool solved = false;
110  Motion *soln;
111 
112  while (ptc() == false && !solved)
113  {
114  const std::vector<ProductGraph::State *> lead =
116  {
117  return abstractEdgeWeight(a, b);
118  });
119  buildAvail(lead);
120  solved = explore(lead, soln, exploreTime_);
121  }
122 
123  if (solved)
124  {
125  // build solution path
126  std::vector<Motion *> path;
127  while (soln != nullptr)
128  {
129  path.push_back(soln);
130  soln = soln->parent;
131  }
132  auto pc(std::make_shared<PathControl>(si_));
133  for (int i = path.size() - 1; i >= 0; --i)
134  {
135  if (path[i]->parent != nullptr)
136  pc->append(path[i]->state, path[i]->control, path[i]->steps * ltlsi_->getPropagationStepSize());
137  else
138  pc->append(path[i]->state);
139  }
140  pdef_->addSolutionPath(pc);
141  }
142 
143  OMPL_INFORM("Created %u states", motions_.size());
144  return base::PlannerStatus(solved, false);
145 }
146 
147 void ompl::control::LTLPlanner::getTree(std::vector<base::State *> &tree) const
148 {
149  tree.resize(motions_.size());
150  for (unsigned int i = 0; i < motions_.size(); ++i)
151  tree[i] = motions_[i]->state;
152 }
153 
154 std::vector<ompl::control::ProductGraph::State *>
155 ompl::control::LTLPlanner::getHighLevelPath(const std::vector<base::State *> &path, ProductGraph::State *start) const
156 {
157  std::vector<ProductGraph::State *> hlPath(path.size());
158  hlPath[0] = (start != nullptr ? start : ltlsi_->getProdGraphState(path[0]));
159  for (unsigned int i = 1; i < path.size(); ++i)
160  {
161  hlPath[i] = ltlsi_->getProdGraphState(path[i]);
162  if (!hlPath[i]->isValid())
163  OMPL_WARN("High-level path fails automata");
164  }
165  return hlPath;
166 }
167 
169  : state(si->allocState()), control(si->allocControl())
170 {
171 }
172 
174 
175 
177 {
178  motionElems[m] = motions.add(m, 1.);
179 }
180 
182 {
184  /* \todo weight should include freeVolume, for cases in which decomposition
185  does not respect obstacles. */
186  info.weight = ((info.motions.size() + 1) * info.volume) / (info.autWeight * (info.numSel + 1) * (info.numSel + 1));
187  return info.weight;
188 }
189 
191 {
193  info.numSel = 0;
194  info.pdfElem = nullptr;
195  info.volume = abstraction_->getRegionVolume(as);
196  unsigned int autDist = std::max(abstraction_->getCosafeAutDistance(as), abstraction_->getSafeAutDistance(as));
197  //\todo try something larger than epsilon
198  if (autDist == 0)
199  info.autWeight = std::numeric_limits<double>::epsilon();
200  else
201  info.autWeight = autDist;
202  info.weight = info.volume / info.autWeight;
203 }
204 
205 void ompl::control::LTLPlanner::buildAvail(const std::vector<ProductGraph::State *> &lead)
206 {
207  for (unsigned int i = 0; i < availDist_.size(); ++i)
208  abstractInfo_[availDist_[i]].pdfElem = nullptr;
209  availDist_.clear();
210  unsigned int numTreePts = 1;
211  for (int i = lead.size() - 1; i >= 0; --i)
212  {
213  ProductGraph::State *as = lead[i];
215  if (!info.motions.empty())
216  {
217  info.pdfElem = availDist_.add(as, info.weight);
218  numTreePts += info.motions.size();
219  if (rng_.uniform01() < 0.5)
220  break;
221  }
222  }
223 }
224 
225 bool ompl::control::LTLPlanner::explore(const std::vector<ProductGraph::State *> &lead, Motion *&soln, double duration)
226 {
227  bool solved = false;
229  base::GoalPtr goal = pdef_->getGoal();
230  while (!ptc() && !solved)
231  {
233  ++abstractInfo_[as].numSel;
234  updateWeight(as);
235 
236  PDF<Motion *> &motions = abstractInfo_[as].motions;
237  Motion *v = motions.sample(rng_.uniform01());
238  PDF<Motion *>::Element *velem = abstractInfo_[as].motionElems[v];
239  double vweight = motions.getWeight(velem);
240  if (vweight > 1e-20)
241  motions.update(velem, vweight / (vweight + 1.));
242 
243  Control *rctrl = ltlsi_->allocControl();
244  controlSampler_->sampleNext(rctrl, v->control, v->state);
245  unsigned int cd =
247 
248  base::State *newState = si_->allocState();
249  cd = ltlsi_->propagateWhileValid(v->state, rctrl, cd, newState);
250  if (cd < ltlsi_->getMinControlDuration())
251  {
252  si_->freeState(newState);
253  ltlsi_->freeControl(rctrl);
254  continue;
255  }
256  auto *m = new Motion();
257  m->state = newState;
258  m->control = rctrl;
259  m->steps = cd;
260  m->parent = v;
261  // Since the state was determined to be valid by SpaceInformation, we don't need to check automaton states
262  m->abstractState = ltlsi_->getProdGraphState(m->state);
263  motions_.push_back(m);
264 
265  abstractInfo_[m->abstractState].addMotion(m);
266  updateWeight(m->abstractState);
267  // update weight if hl state already exists in avail
268  if (abstractInfo_[m->abstractState].pdfElem != nullptr)
269  availDist_.update(abstractInfo_[m->abstractState].pdfElem, abstractInfo_[m->abstractState].weight);
270  else
271  {
272  // otherwise, only add hl state to avail if it already exists in lead
273  if (std::find(lead.begin(), lead.end(), m->abstractState) != lead.end())
274  {
276  availDist_.add(m->abstractState, abstractInfo_[m->abstractState].weight);
277  abstractInfo_[m->abstractState].pdfElem = elem;
278  }
279  }
280 
281  solved = goal->isSatisfied(m->state);
282  if (solved)
283  {
284  soln = m;
285  break;
286  }
287  }
288  return solved;
289 }
290 
292 {
293  const ProductGraphStateInfo &infoA = abstractInfo_.find(a)->second;
294  const ProductGraphStateInfo &infoB = abstractInfo_.find(b)->second;
295  return 1. / (infoA.weight * infoB.weight);
296 }
297 
298 void ompl::control::LTLPlanner::clearMotions()
299 {
300  availDist_.clear();
301  for (auto m : motions_)
302  {
303  if (m->state != nullptr)
304  si_->freeState(m->state);
305  if (m->control != nullptr)
306  ltlsi_->freeControl(m->control);
307  delete m;
308  }
309  motions_.clear();
310  pis_.clear();
311  pis_.update();
312 }
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:203
LTLPlanner(const LTLSpaceInformationPtr &si, ProductGraphPtr a, double exploreTime=0.5)
Create an LTLPlanner with a given space and product graph. Accepts an optional third parameter to con...
Definition: LTLPlanner.cpp:52
virtual double abstractEdgeWeight(ProductGraph::State *a, ProductGraph::State *b) const
Returns the weight of an edge between two given high-level states, which we compute as the product of...
Definition: LTLPlanner.cpp:291
double getPropagationStepSize() const
Propagation is performed at integer multiples of a specified step size. This function returns the val...
void addMotion(Motion *m)
Adds a tree motion to an info object. This method is called whenever a new tree motion is created in ...
Definition: LTLPlanner.cpp:176
base::State * state
The state contained by the motion.
Definition: LTLPlanner.h:114
unsigned int getMinControlDuration() const
Get the minimum number of steps a control is propagated for.
const LTLSpaceInformation * ltlsi_
Handle to the control::SpaceInformation object.
Definition: LTLPlanner.h:180
double exploreTime_
Time to spend exploring each lead.
Definition: LTLPlanner.h:198
unsigned int propagateWhileValid(const base::State *state, const Control *control, int steps, base::State *result) const
Propagate the model of the system forward, starting at a given state, with a given control...
void nullControl(Control *control) const
Make the control have no effect if it were to be applied to a state for any amount of time...
void getTree(std::vector< base::State *> &tree) const
Helper debug method to access this planner&#39;s underlying tree of states.
Definition: LTLPlanner.cpp:147
Definition of an abstract control.
Definition: Control.h:47
PDF< ProductGraph::State * > availDist_
Used to sample nonempty regions in which to promote expansion.
Definition: LTLPlanner.h:186
ProductGraph::State * prodStart_
Start state in product graph.
Definition: LTLPlanner.h:195
virtual void initAbstractInfo(ProductGraph::State *as)
Initializes the info object for a new high-level state.
Definition: LTLPlanner.cpp:190
virtual double updateWeight(ProductGraph::State *as)
Updates and returns the weight of an abstraction state.
Definition: LTLPlanner.cpp:181
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
STL namespace.
ControlSamplerPtr allocControlSampler() const
Allocate a control sampler.
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: Planner.cpp:113
~LTLPlanner() override
Clears all memory belonging to this LTLPlanner .
Definition: LTLPlanner.cpp:61
Control * allocControl() const
Allocate memory for a control.
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition: Planner.h:409
Representation of a motion.
Definition: LTLPlanner.h:99
base::StateSamplerPtr sampler_
State sampler.
Definition: LTLPlanner.h:174
std::unordered_map< ProductGraph::State *, ProductGraphStateInfo > abstractInfo_
Map of abstraction states to their details.
Definition: LTLPlanner.h:201
Control * control
The control contained by the motion.
Definition: LTLPlanner.h:117
bool haveMoreStartStates() const
Check if there are more potential start states.
Definition: Planner.cpp:335
virtual ~Motion()
Motion destructor does not clear memory. Deletions should be performed by the LTLPlanner.
A container that supports probabilistic sampling over weighted data.
Definition: PDF.h:48
double uniform01()
Generate a random real between 0 and 1.
Definition: RandomNumbers.h:68
A shared pointer wrapper for ompl::control::LTLSpaceInformation.
ControlSamplerPtr controlSampler_
Control sampler.
Definition: LTLPlanner.h:177
std::vector< Motion * > motions_
Set of all motions.
Definition: LTLPlanner.h:192
PlannerTerminationCondition timedPlannerTerminationCondition(double duration)
Return a termination condition that will become true duration seconds in the future (wall-time) ...
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
void setup() override
Initializes LTLPlanner data structures.
Definition: LTLPlanner.cpp:66
std::vector< ProductGraph::State * > getHighLevelPath(const std::vector< base::State *> &path, ProductGraph::State *start=nullptr) const
Helper debug method to return the sequence of high-level product graph states corresponding to a sequ...
Definition: LTLPlanner.cpp:155
virtual bool explore(const std::vector< ProductGraph::State *> &lead, Motion *&soln, double duration)
Expand the tree of motions along a given lead for a given duration of time. Returns true if a solutio...
Definition: LTLPlanner.cpp:225
double getWeight(const Element *elem) const
Returns the current weight of the given Element.
Definition: PDF.h:171
unsigned int getMaxControlDuration() const
Get the maximum number of steps a control is propagated for.
RNG rng_
A random number generator.
Definition: LTLPlanner.h:189
void clear()
Clear all stored information.
Definition: Planner.cpp:157
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Continues solving until a solution is found or a given planner termination condition is met...
Definition: LTLPlanner.cpp:79
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: Planner.cpp:87
A State of a ProductGraph represents a vertex in the graph-based Cartesian product represented by the...
Definition: ProductGraph.h:83
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
void clear() override
Clears all datastructures belonging to this LTLPlanner.
Definition: LTLPlanner.cpp:71
Definition of an abstract state.
Definition: State.h:49
virtual void checkValidity()
Check to see if the planner is in a working state (setup has been called, a goal was set...
Definition: Planner.cpp:101
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
PlannerInputStates pis_
Utility class to extract valid input states.
Definition: Planner.h:412
A class that will hold data contained in the PDF.
Definition: PDF.h:52
ProductGraphPtr abstraction_
The high level abstaction used to grow the tree structure.
Definition: LTLPlanner.h:183
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:418
const State * nextStart()
Return the next valid start state or nullptr if no more valid start states are available.
Definition: Planner.cpp:227
void update(Element *elem, const double w)
Updates the data in the given Element with a new weight value.
Definition: PDF.h:155
_T & sample(double r) const
Returns a piece of data from the PDF according to the input sampling value, which must be between 0 a...
Definition: PDF.h:132
bool update()
Set the space information and problem definition this class operates on, based on the available plann...
Definition: Planner.cpp:176
A shared pointer wrapper for ompl::control::ProductGraph.
Motion()=default
Default constructor for Motion.
A shared pointer wrapper for ompl::base::Goal.
void freeControl(Control *control) const
Free the memory of a control.
virtual void buildAvail(const std::vector< ProductGraph::State *> &lead)
Compute a set of high-level states along a lead to be considered for expansion.
Definition: LTLPlanner.cpp:205
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:406
Space information containing necessary information for planning with controls. setup() needs to be ca...
Motion * parent
The parent motion in the tree.
Definition: LTLPlanner.h:120
A structure to hold measurement information for a high-level state, as well as the set of tree motion...
Definition: LTLPlanner.h:132
T * as()
Cast this instance to a desired type.
Definition: Planner.h:238
ProductGraph::State * abstractState
The high-level state to which this motion belongs.
Definition: LTLPlanner.h:126
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68