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