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 
101  prevSolutionCost_ = opt_->infiniteCost();
102 }
103 
105 {
106  Planner::clear();
107  sampler_.reset();
108  freeMemory();
109  if (nn_)
110  nn_->clear();
111  if (witnesses_)
112  witnesses_->clear();
113  if (opt_)
114  prevSolutionCost_ = opt_->infiniteCost();
115 }
116 
118 {
119  if (nn_)
120  {
121  std::vector<Motion *> motions;
122  nn_->list(motions);
123  for (auto &motion : motions)
124  {
125  if (motion->state_)
126  si_->freeState(motion->state_);
127  delete motion;
128  }
129  }
130  if (witnesses_)
131  {
132  std::vector<Motion *> witnesses;
133  witnesses_->list(witnesses);
134  for (auto &witness : witnesses)
135  {
136  if (witness->state_)
137  si_->freeState(witness->state_);
138  delete witness;
139  }
140  }
141 
142  for (auto &i : prevSolution_)
143  {
144  if (i)
145  si_->freeState(i);
146  }
147  prevSolution_.clear();
148 }
149 
151 {
152  std::vector<Motion *> ret;
153  Motion *selected = nullptr;
154  base::Cost bestCost = opt_->infiniteCost();
155  nn_->nearestR(sample, selectionRadius_, ret);
156  for (auto &i : ret)
157  {
158  if (!i->inactive_ && opt_->isCostBetterThan(i->accCost_, bestCost))
159  {
160  bestCost = i->accCost_;
161  selected = i;
162  }
163  }
164  if (selected == nullptr)
165  {
166  int k = 1;
167  while (selected == nullptr)
168  {
169  nn_->nearestK(sample, k, ret);
170  for (unsigned int i = 0; i < ret.size() && selected == nullptr; i++)
171  if (!ret[i]->inactive_)
172  selected = ret[i];
173  k += 5;
174  }
175  }
176  return selected;
177 }
178 
180 {
181  if (witnesses_->size() > 0)
182  {
183  auto *closest = static_cast<Witness *>(witnesses_->nearest(node));
184  if (distanceFunction(closest, node) > pruningRadius_)
185  {
186  closest = new Witness(si_);
187  closest->linkRep(node);
188  si_->copyState(closest->state_, node->state_);
189  witnesses_->add(closest);
190  }
191  return closest;
192  }
193  else
194  {
195  auto *closest = new Witness(si_);
196  closest->linkRep(node);
197  si_->copyState(closest->state_, node->state_);
198  witnesses_->add(closest);
199  return closest;
200  }
201 }
202 
204 {
205  // sample random point to serve as a direction
206  base::State *xstate = si_->allocState();
207  sampler_->sampleUniform(xstate);
208 
209  // sample length of step from (0 - maxDistance_]
210  double step = rng_.uniformReal(0, maxDistance_);
211 
212  // take a step of length step towards the random state
213  double d = si_->distance(m->state_, xstate);
214  si_->getStateSpace()->interpolate(m->state_, xstate, step / d, xstate);
215  si_->enforceBounds(xstate);
216 
217  return xstate;
218 }
219 
221 {
222  checkValidity();
223  base::Goal *goal = pdef_->getGoal().get();
224  auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
225 
226  while (const base::State *st = pis_.nextStart())
227  {
228  auto *motion = new Motion(si_);
229  si_->copyState(motion->state_, st);
230  nn_->add(motion);
231  motion->accCost_ = opt_->identityCost();
232  findClosestWitness(motion);
233  }
234 
235  if (nn_->size() == 0)
236  {
237  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
239  }
240 
241  if (!sampler_)
242  sampler_ = si_->allocStateSampler();
243 
244  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
245 
246  Motion *solution = nullptr;
247  Motion *approxsol = nullptr;
248  double approxdif = std::numeric_limits<double>::infinity();
249  bool sufficientlyShort = false;
250  auto *rmotion = new Motion(si_);
251  base::State *rstate = rmotion->state_;
252  base::State *xstate = si_->allocState();
253 
254  unsigned iterations = 0;
255 
256  while (ptc == false)
257  {
258  /* sample random state (with goal biasing) */
259  bool attemptToReachGoal = (goal_s && rng_.uniform01() < goalBias_ && goal_s->canSample());
260  if (attemptToReachGoal)
261  goal_s->sampleGoal(rstate);
262  else
263  sampler_->sampleUniform(rstate);
264 
265  /* find closest state in the tree */
266  Motion *nmotion = selectNode(rmotion);
267 
268  base::State *dstate = rstate;
269  double d = si_->distance(nmotion->state_, rstate);
270 
271  attemptToReachGoal = rng_.uniform01() < .5;
272  if (attemptToReachGoal)
273  {
274  if (d > maxDistance_)
275  {
276  si_->getStateSpace()->interpolate(nmotion->state_, rstate, maxDistance_ / d, xstate);
277  dstate = xstate;
278  }
279  }
280  else
281  {
282  dstate = monteCarloProp(nmotion);
283  }
284 
285  si_->copyState(rstate, dstate);
286 
287  if (si_->checkMotion(nmotion->state_, rstate))
288  {
289  base::Cost incCost = opt_->motionCost(nmotion->state_, rstate);
290  base::Cost cost = opt_->combineCosts(nmotion->accCost_, incCost);
291  Witness *closestWitness = findClosestWitness(rmotion);
292 
293  if (closestWitness->rep_ == rmotion || opt_->isCostBetterThan(cost, closestWitness->rep_->accCost_))
294  {
295  Motion *oldRep = closestWitness->rep_;
296  /* create a motion */
297  auto *motion = new Motion(si_);
298  motion->accCost_ = cost;
299  si_->copyState(motion->state_, rstate);
300 
301  if (!attemptToReachGoal)
302  si_->freeState(dstate);
303  motion->parent_ = nmotion;
304  nmotion->numChildren_++;
305  closestWitness->linkRep(motion);
306 
307  nn_->add(motion);
308  double dist = 0.0;
309  bool solv = goal->isSatisfied(motion->state_, &dist);
310  if (solv && opt_->isCostBetterThan(motion->accCost_, prevSolutionCost_))
311  {
312  approxdif = dist;
313  solution = motion;
314 
315  for (auto &i : prevSolution_)
316  if (i)
317  si_->freeState(i);
318  prevSolution_.clear();
319  Motion *solTrav = solution;
320  while (solTrav != nullptr)
321  {
322  prevSolution_.push_back(si_->cloneState(solTrav->state_));
323  solTrav = solTrav->parent_;
324  }
325  prevSolutionCost_ = solution->accCost_;
326 
327  OMPL_INFORM("Found solution with cost %.2f", solution->accCost_.value());
328  sufficientlyShort = opt_->isSatisfied(solution->accCost_);
329  if (sufficientlyShort)
330  {
331  break;
332  }
333  }
334  if (solution == nullptr && dist < approxdif)
335  {
336  approxdif = dist;
337  approxsol = motion;
338 
339  for (auto &i : prevSolution_)
340  {
341  if (i)
342  si_->freeState(i);
343  }
344  prevSolution_.clear();
345  Motion *solTrav = approxsol;
346  while (solTrav != nullptr)
347  {
348  prevSolution_.push_back(si_->cloneState(solTrav->state_));
349  solTrav = solTrav->parent_;
350  }
351  }
352 
353  if (oldRep != rmotion)
354  {
355  while (oldRep->inactive_ && oldRep->numChildren_ == 0)
356  {
357  oldRep->inactive_ = true;
358  nn_->remove(oldRep);
359 
360  if (oldRep->state_)
361  si_->freeState(oldRep->state_);
362 
363  oldRep->state_ = nullptr;
364  oldRep->parent_->numChildren_--;
365  Motion *oldRepParent = oldRep->parent_;
366  delete oldRep;
367  oldRep = oldRepParent;
368  }
369  }
370  }
371  }
372  iterations++;
373  }
374 
375  bool solved = false;
376  bool approximate = false;
377  if (solution == nullptr)
378  {
379  solution = approxsol;
380  approximate = true;
381  }
382 
383  if (solution != nullptr)
384  {
385  /* set the solution path */
386  auto path(std::make_shared<PathGeometric>(si_));
387  for (int i = prevSolution_.size() - 1; i >= 0; --i)
388  path->append(prevSolution_[i]);
389  solved = true;
390  pdef_->addSolutionPath(path, approximate, approxdif, getName());
391  }
392 
393  si_->freeState(xstate);
394  if (rmotion->state_)
395  si_->freeState(rmotion->state_);
396  rmotion->state_ = nullptr;
397  delete rmotion;
398 
399  OMPL_INFORM("%s: Created %u states in %u iterations", getName().c_str(), nn_->size(), iterations);
400 
401  return {solved, approximate};
402 }
403 
405 {
406  Planner::getPlannerData(data);
407 
408  std::vector<Motion *> motions;
409  std::vector<Motion *> allMotions;
410  if (nn_)
411  nn_->list(motions);
412 
413  for (auto &motion : motions)
414  if (motion->numChildren_ == 0)
415  allMotions.push_back(motion);
416  for (unsigned i = 0; i < allMotions.size(); i++)
417  if (allMotions[i]->getParent() != nullptr)
418  allMotions.push_back(allMotions[i]->getParent());
419 
420  if (prevSolution_.size() != 0)
421  data.addGoalVertex(base::PlannerDataVertex(prevSolution_[0]));
422 
423  for (auto &allMotion : allMotions)
424  {
425  if (allMotion->getParent() == nullptr)
426  data.addStartVertex(base::PlannerDataVertex(allMotion->getState()));
427  else
428  data.addEdge(base::PlannerDataVertex(allMotion->getParent()->getState()),
429  base::PlannerDataVertex(allMotion->getState()));
430  }
431 }
base::State * monteCarloProp(Motion *m)
Randomly propagate a new edge.
Definition: SST.cpp:203
bool inactive_
If inactive, this node is not considered for selection.
Definition: SST.h:203
unsigned numChildren_
Number of children.
Definition: SST.h:200
double getPruningRadius() const
Get the pruning radius the planner is using.
Definition: SST.h:148
void setPruningRadius(double pruningRadius)
Set the radius for pruning nodes.
Definition: SST.h:142
Definition of an abstract state.
Definition: State.h:50
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:410
Motion * parent_
The parent motion in the exploration tree.
Definition: SST.h:197
double value() const
The value of the cost.
Definition: Cost.h:56
void clear() override
Clear datastructures. Call this function if the input data to the planner has changed and you do not ...
Definition: SST.cpp:104
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:48
#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:175
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:179
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Continue solving for some amount of time. Return true if solution was found.
Definition: SST.cpp:220
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:429
bool directed
Flag indicating whether the planner is able to account for the fact that the validity of a motion fro...
Definition: Planner.h:212
void freeMemory()
Free the memory allocated by this planner.
Definition: SST.cpp:117
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:49
SST(const base::SpaceInformationPtr &si)
Constructor.
Definition: SST.cpp:45
double getGoalBias() const
Get the goal bias the planner is using.
Definition: SST.h:92
base::Cost prevSolutionCost_
The best solution cost we found so far.
Definition: SST.h:279
void setSelectionRadius(double selectionRadius)
Set the radius for selecting nodes relative to random sample.
Definition: SST.h:121
std::vector< base::State * > prevSolution_
The best solution we found so far.
Definition: SST.h:276
Abstract definition of goals.
Definition: Goal.h:63
double getSelectionRadius() const
Get the selection radius the planner is using.
Definition: SST.h:127
#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:194
Motion * selectNode(Motion *sample)
Finds the best node in the tree withing the selection radius around a random sample.
Definition: SST.cpp:150
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:108
void setGoalBias(double goalBias)
Definition: SST.h:86
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:202
Motion * rep_
The node in the tree that is within the pruning radius.
Definition: SST.h:229
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: SST.h:102
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:404
Abstract definition of a goal region that can be sampled.
Representation of a motion.
Definition: SST.h:171
@ INVALID_START
Invalid start state or no start state specified.
Definition: PlannerStatus.h:56
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:59
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: SST.cpp:65