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