SST.cpp
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, Rutgers the State University of New Jersey, New Brunswick
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 Rutgers 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 /* Authors: Zakary Littlefield */
36 
37 #include "ompl/geometric/planners/sst/SST.h"
38 #include "ompl/base/goals/GoalSampleableRegion.h"
39 #include "ompl/base/objectives/MinimaxObjective.h"
40 #include "ompl/base/objectives/MaximizeMinClearanceObjective.h"
41 #include "ompl/base/objectives/PathLengthOptimizationObjective.h"
42 #include "ompl/tools/config/SelfConfig.h"
43 #include <limits>
44 
45 ompl::geometric::SST::SST(const base::SpaceInformationPtr &si) : base::Planner(si, "SST")
46 {
48  specs_.directed = true;
49  prevSolution_.clear();
50 
51  Planner::declareParam<double>("range", this, &SST::setRange, &SST::getRange, ".1:.1:100");
52  Planner::declareParam<double>("goal_bias", this, &SST::setGoalBias, &SST::getGoalBias, "0.:.05:1.");
53  Planner::declareParam<double>("selection_radius", this, &SST::setSelectionRadius, &SST::getSelectionRadius, "0.:.1:"
54  "100");
55  Planner::declareParam<double>("pruning_radius", this, &SST::setPruningRadius, &SST::getPruningRadius, "0.:.1:100");
56 
57  addPlannerProgressProperty("best cost REAL", [this] { return std::to_string(this->prevSolutionCost_.value()); });
58 }
59 
60 ompl::geometric::SST::~SST()
61 {
62  freeMemory();
63 }
64 
66 {
68  if (!nn_)
69  nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
70  nn_->setDistanceFunction([this](const Motion *a, const Motion *b)
71  {
72  return distanceFunction(a, b);
73  });
74  if (!witnesses_)
75  witnesses_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
76  witnesses_->setDistanceFunction([this](const Motion *a, const Motion *b)
77  {
78  return distanceFunction(a, b);
79  });
80 
81  if (pdef_)
82  {
83  if (pdef_->hasOptimizationObjective())
84  {
85  opt_ = pdef_->getOptimizationObjective();
86  if (dynamic_cast<base::MaximizeMinClearanceObjective *>(opt_.get()) ||
87  dynamic_cast<base::MinimaxObjective *>(opt_.get()))
88  OMPL_WARN("%s: Asymptotic near-optimality has only been proven with Lipschitz continuous cost "
89  "functions w.r.t. state and control. This optimization objective will result in undefined "
90  "behavior",
91  getName().c_str());
92  }
93  else
94  {
95  OMPL_WARN("%s: No optimization object set. Using path length", getName().c_str());
96  opt_ = std::make_shared<base::PathLengthOptimizationObjective>(si_);
97  pdef_->setOptimizationObjective(opt_);
98  }
99  }
100  else
101  {
102  OMPL_WARN("%s: No optimization object set. Using path length", getName().c_str());
103  opt_ = std::make_shared<base::PathLengthOptimizationObjective>(si_);
104  }
105  prevSolutionCost_ = opt_->infiniteCost();
106 }
107 
109 {
110  Planner::clear();
111  sampler_.reset();
112  freeMemory();
113  if (nn_)
114  nn_->clear();
115  if (witnesses_)
116  witnesses_->clear();
117  if (opt_)
118  prevSolutionCost_ = opt_->infiniteCost();
119 }
120 
122 {
123  if (nn_)
124  {
125  std::vector<Motion *> motions;
126  nn_->list(motions);
127  for (auto &motion : motions)
128  {
129  if (motion->state_)
130  si_->freeState(motion->state_);
131  delete motion;
132  }
133  }
134  if (witnesses_)
135  {
136  std::vector<Motion *> witnesses;
137  witnesses_->list(witnesses);
138  for (auto &witness : witnesses)
139  {
140  if (witness->state_)
141  si_->freeState(witness->state_);
142  delete witness;
143  }
144  }
145 
146  for (auto &i : prevSolution_)
147  {
148  if (i)
149  si_->freeState(i);
150  }
151  prevSolution_.clear();
152 }
153 
155 {
156  std::vector<Motion *> ret;
157  Motion *selected = nullptr;
158  base::Cost bestCost = opt_->infiniteCost();
159  nn_->nearestR(sample, selectionRadius_, ret);
160  for (auto &i : ret)
161  {
162  if (!i->inactive_ && opt_->isCostBetterThan(i->accCost_, bestCost))
163  {
164  bestCost = i->accCost_;
165  selected = i;
166  }
167  }
168  if (selected == nullptr)
169  {
170  int k = 1;
171  while (selected == nullptr)
172  {
173  nn_->nearestK(sample, k, ret);
174  for (unsigned int i = 0; i < ret.size() && selected == nullptr; i++)
175  if (!ret[i]->inactive_)
176  selected = ret[i];
177  k += 5;
178  }
179  }
180  return selected;
181 }
182 
184 {
185  if (witnesses_->size() > 0)
186  {
187  auto *closest = static_cast<Witness *>(witnesses_->nearest(node));
188  if (distanceFunction(closest, node) > pruningRadius_)
189  {
190  closest = new Witness(si_);
191  closest->linkRep(node);
192  si_->copyState(closest->state_, node->state_);
193  witnesses_->add(closest);
194  }
195  return closest;
196  }
197  else
198  {
199  auto *closest = new Witness(si_);
200  closest->linkRep(node);
201  si_->copyState(closest->state_, node->state_);
202  witnesses_->add(closest);
203  return closest;
204  }
205 }
206 
208 {
209  // sample random point to serve as a direction
210  base::State *xstate = si_->allocState();
211  sampler_->sampleUniform(xstate);
212 
213  // sample length of step from (0 - maxDistance_]
214  double step = rng_.uniformReal(0, maxDistance_);
215 
216  // take a step of length step towards the random state
217  double d = si_->distance(m->state_, xstate);
218  si_->getStateSpace()->interpolate(m->state_, xstate, step / d, xstate);
219  si_->enforceBounds(xstate);
220 
221  return xstate;
222 }
223 
225 {
226  checkValidity();
227  base::Goal *goal = pdef_->getGoal().get();
228  auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
229 
230  while (const base::State *st = pis_.nextStart())
231  {
232  auto *motion = new Motion(si_);
233  si_->copyState(motion->state_, st);
234  nn_->add(motion);
235  motion->accCost_ = opt_->identityCost();
236  findClosestWitness(motion);
237  }
238 
239  if (nn_->size() == 0)
240  {
241  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
243  }
244 
245  if (!sampler_)
246  sampler_ = si_->allocStateSampler();
247 
248  const base::ReportIntermediateSolutionFn intermediateSolutionCallback = pdef_->getIntermediateSolutionCallback();
249 
250  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
251 
252  Motion *solution = nullptr;
253  Motion *approxsol = nullptr;
254  double approxdif = std::numeric_limits<double>::infinity();
255  bool sufficientlyShort = false;
256  auto *rmotion = new Motion(si_);
257  base::State *rstate = rmotion->state_;
258  base::State *xstate = si_->allocState();
259 
260  unsigned iterations = 0;
261 
262  while (ptc == false)
263  {
264  /* sample random state (with goal biasing) */
265  bool attemptToReachGoal = (goal_s && rng_.uniform01() < goalBias_ && goal_s->canSample());
266  if (attemptToReachGoal)
267  goal_s->sampleGoal(rstate);
268  else
269  sampler_->sampleUniform(rstate);
270 
271  /* find closest state in the tree */
272  Motion *nmotion = selectNode(rmotion);
273 
274  base::State *dstate = rstate;
275  double d = si_->distance(nmotion->state_, rstate);
276 
277  attemptToReachGoal = rng_.uniform01() < .5;
278  if (attemptToReachGoal)
279  {
280  if (d > maxDistance_)
281  {
282  si_->getStateSpace()->interpolate(nmotion->state_, rstate, maxDistance_ / d, xstate);
283  dstate = xstate;
284  }
285  }
286  else
287  {
288  dstate = monteCarloProp(nmotion);
289  }
290 
291  si_->copyState(rstate, dstate);
292 
293  if (si_->checkMotion(nmotion->state_, rstate))
294  {
295  base::Cost incCost = opt_->motionCost(nmotion->state_, rstate);
296  base::Cost cost = opt_->combineCosts(nmotion->accCost_, incCost);
297  Witness *closestWitness = findClosestWitness(rmotion);
298 
299  if (closestWitness->rep_ == rmotion || opt_->isCostBetterThan(cost, closestWitness->rep_->accCost_))
300  {
301  Motion *oldRep = closestWitness->rep_;
302  /* create a motion */
303  auto *motion = new Motion(si_);
304  motion->accCost_ = cost;
305  si_->copyState(motion->state_, rstate);
306 
307  if (!attemptToReachGoal)
308  si_->freeState(dstate);
309  motion->parent_ = nmotion;
310  nmotion->numChildren_++;
311  closestWitness->linkRep(motion);
312 
313  nn_->add(motion);
314  double dist = 0.0;
315  bool solv = goal->isSatisfied(motion->state_, &dist);
316  if (solv && opt_->isCostBetterThan(motion->accCost_, prevSolutionCost_))
317  {
318  approxdif = dist;
319  solution = motion;
320 
321  for (auto &i : prevSolution_)
322  if (i)
323  si_->freeState(i);
324  prevSolution_.clear();
325  Motion *solTrav = solution;
326  while (solTrav != nullptr)
327  {
328  prevSolution_.push_back(si_->cloneState(solTrav->state_));
329  solTrav = solTrav->parent_;
330  }
331  prevSolutionCost_ = solution->accCost_;
332 
333  OMPL_INFORM("Found solution with cost %.2f", solution->accCost_.value());
334  if (intermediateSolutionCallback)
335  {
336  // the callback requires a vector with const elements -> create a copy
337  std::vector<const base::State *> prevSolutionConst(prevSolution_.begin(), prevSolution_.end());
338  intermediateSolutionCallback(this, prevSolutionConst, prevSolutionCost_);
339  }
340  sufficientlyShort = opt_->isSatisfied(solution->accCost_);
341  if (sufficientlyShort)
342  {
343  break;
344  }
345  }
346  if (solution == nullptr && dist < approxdif)
347  {
348  approxdif = dist;
349  approxsol = motion;
350 
351  for (auto &i : prevSolution_)
352  {
353  if (i)
354  si_->freeState(i);
355  }
356  prevSolution_.clear();
357  Motion *solTrav = approxsol;
358  while (solTrav != nullptr)
359  {
360  prevSolution_.push_back(si_->cloneState(solTrav->state_));
361  solTrav = solTrav->parent_;
362  }
363  }
364 
365  if (oldRep != rmotion)
366  {
367  while (oldRep->inactive_ && oldRep->numChildren_ == 0)
368  {
369  oldRep->inactive_ = true;
370  nn_->remove(oldRep);
371 
372  if (oldRep->state_)
373  si_->freeState(oldRep->state_);
374 
375  oldRep->state_ = nullptr;
376  oldRep->parent_->numChildren_--;
377  Motion *oldRepParent = oldRep->parent_;
378  delete oldRep;
379  oldRep = oldRepParent;
380  }
381  }
382  }
383  }
384  iterations++;
385  }
386 
387  bool solved = false;
388  bool approximate = false;
389  if (solution == nullptr)
390  {
391  solution = approxsol;
392  approximate = true;
393  }
394 
395  if (solution != nullptr)
396  {
397  /* set the solution path */
398  auto path(std::make_shared<PathGeometric>(si_));
399  for (int i = prevSolution_.size() - 1; i >= 0; --i)
400  path->append(prevSolution_[i]);
401  solved = true;
402  pdef_->addSolutionPath(path, approximate, approxdif, getName());
403  }
404 
405  si_->freeState(xstate);
406  if (rmotion->state_)
407  si_->freeState(rmotion->state_);
408  rmotion->state_ = nullptr;
409  delete rmotion;
410 
411  OMPL_INFORM("%s: Created %u states in %u iterations", getName().c_str(), nn_->size(), iterations);
412 
413  return {solved, approximate};
414 }
415 
417 {
418  Planner::getPlannerData(data);
419 
420  std::vector<Motion *> motions;
421  std::vector<Motion *> allMotions;
422  if (nn_)
423  nn_->list(motions);
424 
425  for (auto &motion : motions)
426  if (motion->numChildren_ == 0)
427  allMotions.push_back(motion);
428  for (unsigned i = 0; i < allMotions.size(); i++)
429  if (allMotions[i]->getParent() != nullptr)
430  allMotions.push_back(allMotions[i]->getParent());
431 
432  if (prevSolution_.size() != 0)
433  data.addGoalVertex(base::PlannerDataVertex(prevSolution_[0]));
434 
435  for (auto &allMotion : allMotions)
436  {
437  if (allMotion->getParent() == nullptr)
438  data.addStartVertex(base::PlannerDataVertex(allMotion->getState()));
439  else
440  data.addEdge(base::PlannerDataVertex(allMotion->getParent()->getState()),
441  base::PlannerDataVertex(allMotion->getState()));
442  }
443 }
base::State * monteCarloProp(Motion *m)
Randomly propagate a new edge.
Definition: SST.cpp:207
bool inactive_
If inactive, this node is not considered for selection.
Definition: SST.h:299
unsigned numChildren_
Number of children.
Definition: SST.h:296
double getPruningRadius() const
Get the pruning radius the planner is using.
Definition: SST.h:244
void setPruningRadius(double pruningRadius)
Set the radius for pruning nodes.
Definition: SST.h:238
Definition of an abstract state.
Definition: State.h:113
void addPlannerProgressProperty(const std::string &progressPropertyName, const PlannerProgressProperty &prop)
Add a planner progress property called progressPropertyName with a property querying function prop to...
Definition: Planner.h:467
Motion * parent_
The parent motion in the exploration tree.
Definition: SST.h:293
double value() const
The value of the cost.
Definition: Cost.h:152
void clear() override
Clear datastructures. Call this function if the input data to the planner has changed and you do not ...
Definition: SST.cpp:108
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:111
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: Planner.cpp:92
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition: PlannerData.h:238
Objective for attempting to maximize the minimum clearance along a path.
Witness * findClosestWitness(Motion *node)
Find the closest witness node to a newly generated potential node.
Definition: SST.cpp:183
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Continue solving for some amount of time. Return true if solution was found.
Definition: SST.cpp:224
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:486
bool directed
Flag indicating whether the planner is able to account for the fact that the validity of a motion fro...
Definition: Planner.h:269
void freeMemory()
Free the memory allocated by this planner.
Definition: SST.cpp:121
A class to store the exit status of Planner::solve()
SST(const base::SpaceInformationPtr &si)
Constructor.
Definition: SST.cpp:45
double getGoalBias() const
Get the goal bias the planner is using.
Definition: SST.h:188
base::Cost prevSolutionCost_
The best solution cost we found so far.
Definition: SST.h:375
void setSelectionRadius(double selectionRadius)
Set the radius for selecting nodes relative to random sample.
Definition: SST.h:217
std::vector< base::State * > prevSolution_
The best solution we found so far.
Definition: SST.h:372
Abstract definition of goals.
Definition: Goal.h:126
double getSelectionRadius() const
Get the selection radius the planner is using.
Definition: SST.h:223
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
base::State * state_
The state contained by the motion.
Definition: SST.h:290
Motion * selectNode(Motion *sample)
Finds the best node in the tree withing the selection radius around a random sample.
Definition: SST.cpp:154
The cost of a path is defined as the worst state cost over the entire path. This objective attempts t...
double getRange() const
Get the range the planner is using.
Definition: SST.h:204
void setGoalBias(double goalBias)
Definition: SST.h:182
std::function< void(const Planner *, const std::vector< const base::State * > &, const Cost)> ReportIntermediateSolutionFn
When a planner has an intermediate solution (e.g., optimizing planners), a function with this signatu...
unsigned int addStartVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:259
Motion * rep_
The node in the tree that is within the pruning radius.
Definition: SST.h:325
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: SST.h:198
virtual bool addEdge(unsigned int v1, unsigned int v2, const PlannerDataEdge &edge=PlannerDataEdge(), Cost weight=Cost(1.0))
Adds a directed edge between the given vertex indexes. An optional edge structure and weight can be s...
unsigned int addGoalVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
void getPlannerData(base::PlannerData &data) const override
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition: SST.cpp:416
Abstract definition of a goal region that can be sampled.
Representation of a motion.
Definition: SST.h:266
@ INVALID_START
Invalid start state or no start state specified.
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:122
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: SST.cpp:65