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/control/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/base/objectives/MechanicalWorkOptimizationObjective.h"
43 #include "ompl/tools/config/SelfConfig.h"
44 #include <limits>
45 
46 ompl::control::SST::SST(const SpaceInformationPtr &si) : base::Planner(si, "SST")
47 {
49  siC_ = si.get();
50  prevSolution_.clear();
51  prevSolutionControls_.clear();
52  prevSolutionSteps_.clear();
53 
54  goalBias_ = 0.05;
55  selectionRadius_ = 0.2;
56  pruningRadius_ = 0.1;
57 
58  Planner::declareParam<double>("goal_bias", this, &SST::setGoalBias, &SST::getGoalBias, "0.:.05:1.");
59  Planner::declareParam<double>("selection_radius", this, &SST::setSelectionRadius, &SST::getSelectionRadius, "0.:.1:"
60  "100");
61  Planner::declareParam<double>("pruning_radius", this, &SST::setPruningRadius, &SST::getPruningRadius, "0.:.1:100");
62 }
63 
64 ompl::control::SST::~SST()
65 {
66  freeMemory();
67 }
68 
70 {
72  if (!nn_)
73  nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
74  nn_->setDistanceFunction([this](const Motion *a, const Motion *b)
75  {
76  return distanceFunction(a, b);
77  });
78  if (!witnesses_)
79  witnesses_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
80  witnesses_->setDistanceFunction([this](const Motion *a, const Motion *b)
81  {
82  return distanceFunction(a, b);
83  });
84 
85  if (pdef_)
86  {
87  if (pdef_->hasOptimizationObjective())
88  {
89  opt_ = pdef_->getOptimizationObjective();
90  if (dynamic_cast<base::MaximizeMinClearanceObjective *>(opt_.get()) ||
91  dynamic_cast<base::MinimaxObjective *>(opt_.get()))
92  OMPL_WARN("%s: Asymptotic near-optimality has only been proven with Lipschitz continuous cost "
93  "functions w.r.t. state and control. This optimization objective will result in undefined "
94  "behavior",
95  getName().c_str());
96  }
97  else
98  {
99  OMPL_WARN("%s: No optimization object set. Using path length", getName().c_str());
100  opt_ = std::make_shared<base::PathLengthOptimizationObjective>(si_);
101  pdef_->setOptimizationObjective(opt_);
102  }
103  }
104 
105  prevSolutionCost_ = opt_->infiniteCost();
106 }
107 
109 {
110  Planner::clear();
111  sampler_.reset();
112  controlSampler_.reset();
113  freeMemory();
114  if (nn_)
115  nn_->clear();
116  if (witnesses_)
117  witnesses_->clear();
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  if (motion->control_)
132  siC_->freeControl(motion->control_);
133  delete motion;
134  }
135  }
136  if (witnesses_)
137  {
138  std::vector<Motion *> witnesses;
139  witnesses_->list(witnesses);
140  for (auto &witness : witnesses)
141  {
142  delete witness;
143  }
144  }
145  for (auto &i : prevSolution_)
146  {
147  if (i)
148  si_->freeState(i);
149  }
150  prevSolution_.clear();
151  for (auto &prevSolutionControl : prevSolutionControls_)
152  {
153  if (prevSolutionControl)
154  siC_->freeControl(prevSolutionControl);
155  }
156  prevSolutionControls_.clear();
157  prevSolutionSteps_.clear();
158 }
159 
161 {
162  std::vector<Motion *> ret;
163  Motion *selected = nullptr;
164  base::Cost bestCost = opt_->infiniteCost();
165  nn_->nearestR(sample, selectionRadius_, ret);
166  for (auto &i : ret)
167  {
168  if (!i->inactive_ && opt_->isCostBetterThan(i->accCost_, bestCost))
169  {
170  bestCost = i->accCost_;
171  selected = i;
172  }
173  }
174  if (selected == nullptr)
175  {
176  int k = 1;
177  while (selected == nullptr)
178  {
179  nn_->nearestK(sample, k, ret);
180  for (unsigned int i = 0; i < ret.size() && selected == nullptr; i++)
181  if (!ret[i]->inactive_)
182  selected = ret[i];
183  k += 5;
184  }
185  }
186  return selected;
187 }
188 
190 {
191  if (witnesses_->size() > 0)
192  {
193  Witness *closest = static_cast<Witness *>(witnesses_->nearest(node));
194  if (distanceFunction(closest, node) > pruningRadius_)
195  {
196  closest = new Witness(siC_);
197  closest->linkRep(node);
198  si_->copyState(closest->state_, node->state_);
199  witnesses_->add(closest);
200  }
201  return closest;
202  }
203  else
204  {
205  auto *closest = new Witness(siC_);
206  closest->linkRep(node);
207  si_->copyState(closest->state_, node->state_);
208  witnesses_->add(closest);
209  return closest;
210  }
211 }
212 
214 {
215  checkValidity();
216  base::Goal *goal = pdef_->getGoal().get();
217  base::GoalSampleableRegion *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
218 
219  while (const base::State *st = pis_.nextStart())
220  {
221  auto *motion = new Motion(siC_);
222  si_->copyState(motion->state_, st);
223  siC_->nullControl(motion->control_);
224  nn_->add(motion);
225  motion->accCost_ = opt_->identityCost();
226  findClosestWitness(motion);
227  }
228 
229  if (nn_->size() == 0)
230  {
231  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
233  }
234 
235  if (!sampler_)
236  sampler_ = si_->allocStateSampler();
237  if (!controlSampler_)
239 
240  OMPL_INFORM("%s: Starting planning with %u states already in datastructure\n", 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 
247  auto *rmotion = new Motion(siC_);
248  base::State *rstate = rmotion->state_;
249  Control *rctrl = rmotion->control_;
250  base::State *xstate = si_->allocState();
251 
252  unsigned iterations = 0;
253 
254  while (ptc == false)
255  {
256  /* sample random state (with goal biasing) */
257  if (goal_s && rng_.uniform01() < goalBias_ && goal_s->canSample())
258  goal_s->sampleGoal(rstate);
259  else
260  sampler_->sampleUniform(rstate);
261 
262  /* find closest state in the tree */
263  Motion *nmotion = selectNode(rmotion);
264 
265  /* sample a random control that attempts to go towards the random state, and also sample a control duration */
266  controlSampler_->sample(rctrl);
268  unsigned int propCd = siC_->propagateWhileValid(nmotion->state_, rctrl, cd, rstate);
269 
270  if (propCd == cd)
271  {
272  base::Cost incCost = opt_->motionCost(nmotion->state_, rstate);
273  base::Cost cost = opt_->combineCosts(nmotion->accCost_, incCost);
274  Witness *closestWitness = findClosestWitness(rmotion);
275 
276  if (closestWitness->rep_ == rmotion || opt_->isCostBetterThan(cost, closestWitness->rep_->accCost_))
277  {
278  Motion *oldRep = closestWitness->rep_;
279  /* create a motion */
280  auto *motion = new Motion(siC_);
281  motion->accCost_ = cost;
282  si_->copyState(motion->state_, rmotion->state_);
283  siC_->copyControl(motion->control_, rctrl);
284  motion->steps_ = cd;
285  motion->parent_ = nmotion;
286  nmotion->numChildren_++;
287  closestWitness->linkRep(motion);
288 
289  nn_->add(motion);
290  double dist = 0.0;
291  bool solv = goal->isSatisfied(motion->state_, &dist);
292  if (solv && opt_->isCostBetterThan(motion->accCost_, prevSolutionCost_))
293  {
294  approxdif = dist;
295  solution = motion;
296 
297  for (auto &i : prevSolution_)
298  if (i)
299  si_->freeState(i);
300  prevSolution_.clear();
301  for (auto &prevSolutionControl : prevSolutionControls_)
302  if (prevSolutionControl)
303  siC_->freeControl(prevSolutionControl);
304  prevSolutionControls_.clear();
305  prevSolutionSteps_.clear();
306 
307  Motion *solTrav = solution;
308  while (solTrav->parent_ != nullptr)
309  {
310  prevSolution_.push_back(si_->cloneState(solTrav->state_));
311  prevSolutionControls_.push_back(siC_->cloneControl(solTrav->control_));
312  prevSolutionSteps_.push_back(solTrav->steps_);
313  solTrav = solTrav->parent_;
314  }
315  prevSolution_.push_back(si_->cloneState(solTrav->state_));
316  prevSolutionCost_ = solution->accCost_;
317 
318  OMPL_INFORM("Found solution with cost %.2f", solution->accCost_.value());
319  sufficientlyShort = opt_->isSatisfied(solution->accCost_);
320  if (sufficientlyShort)
321  break;
322  }
323  if (solution == nullptr && dist < approxdif)
324  {
325  approxdif = dist;
326  approxsol = motion;
327 
328  for (auto &i : prevSolution_)
329  if (i)
330  si_->freeState(i);
331  prevSolution_.clear();
332  for (auto &prevSolutionControl : prevSolutionControls_)
333  if (prevSolutionControl)
334  siC_->freeControl(prevSolutionControl);
335  prevSolutionControls_.clear();
336  prevSolutionSteps_.clear();
337 
338  Motion *solTrav = approxsol;
339  while (solTrav->parent_ != nullptr)
340  {
341  prevSolution_.push_back(si_->cloneState(solTrav->state_));
342  prevSolutionControls_.push_back(siC_->cloneControl(solTrav->control_));
343  prevSolutionSteps_.push_back(solTrav->steps_);
344  solTrav = solTrav->parent_;
345  }
346  prevSolution_.push_back(si_->cloneState(solTrav->state_));
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  if (oldRep->control_)
358  siC_->freeControl(oldRep->control_);
359 
360  oldRep->state_ = nullptr;
361  oldRep->control_ = nullptr;
362  oldRep->parent_->numChildren_--;
363  Motion *oldRepParent = oldRep->parent_;
364  delete oldRep;
365  oldRep = oldRepParent;
366  }
367  }
368  }
369  }
370  iterations++;
371  }
372 
373  bool solved = false;
374  bool approximate = false;
375  if (solution == nullptr)
376  {
377  solution = approxsol;
378  approximate = true;
379  }
380 
381  if (solution != nullptr)
382  {
383  /* set the solution path */
384  auto path(std::make_shared<PathControl>(si_));
385  for (int i = prevSolution_.size() - 1; i >= 1; --i)
386  path->append(prevSolution_[i], prevSolutionControls_[i - 1],
387  prevSolutionSteps_[i - 1] * siC_->getPropagationStepSize());
388  path->append(prevSolution_[0]);
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  if (rmotion->control_)
397  siC_->freeControl(rmotion->control_);
398  delete rmotion;
399 
400  OMPL_INFORM("%s: Created %u states in %u iterations", getName().c_str(), nn_->size(), iterations);
401 
402  return base::PlannerStatus(solved, approximate);
403 }
404 
406 {
407  Planner::getPlannerData(data);
408 
409  std::vector<Motion *> motions;
410  std::vector<Motion *> allMotions;
411  if (nn_)
412  nn_->list(motions);
413 
414  for (auto &motion : motions)
415  {
416  if (motion->numChildren_ == 0)
417  {
418  allMotions.push_back(motion);
419  }
420  }
421  for (unsigned i = 0; i < allMotions.size(); i++)
422  {
423  if (allMotions[i]->parent_ != nullptr)
424  {
425  allMotions.push_back(allMotions[i]->parent_);
426  }
427  }
428 
429  double delta = siC_->getPropagationStepSize();
430 
431  if (prevSolution_.size() != 0)
433 
434  for (auto m : allMotions)
435  {
436  if (m->parent_)
437  {
438  if (data.hasControls())
439  data.addEdge(base::PlannerDataVertex(m->parent_->state_), base::PlannerDataVertex(m->state_),
440  control::PlannerDataEdgeControl(m->control_, m->steps_ * delta));
441  else
442  data.addEdge(base::PlannerDataVertex(m->parent_->state_), base::PlannerDataVertex(m->state_));
443  }
444  else
445  data.addStartVertex(base::PlannerDataVertex(m->state_));
446  }
447 }
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:212
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:174
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
double getGoalBias() const
Get the goal bias the planner is using.
Definition: SST.h:92
double getPropagationStepSize() const
Propagation is performed at integer multiples of a specified step size. This function returns the val...
unsigned int getMinControlDuration() const
Get the minimum number of steps a control is propagated for.
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: SST.h:265
unsigned numChildren_
Number of children.
Definition: SST.h:206
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...
base::StateSamplerPtr sampler_
State sampler.
Definition: SST.h:256
Definition of an abstract control.
Definition: Control.h:47
Motion * parent_
The parent motion in the exploration tree.
Definition: SST.h:203
std::vector< base::State * > prevSolution_
The best solution we found so far.
Definition: SST.h:284
base::Cost prevSolutionCost_
The best solution cost we found so far.
Definition: SST.h:289
Witness * findClosestWitness(Motion *node)
Find the closest witness node to a newly generated potential node.
Definition: SST.cpp:189
bool inactive_
If inactive, this node is not considered for selection.
Definition: SST.h:209
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
Control * control_
The control contained by the motion.
Definition: SST.h:197
const SpaceInformation * siC_
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition: SST.h:262
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Representation of an edge in PlannerData for planning with controls. This structure encodes a specifi...
Definition: PlannerData.h:60
ControlSamplerPtr allocControlSampler() const
Allocate a control sampler.
ControlSamplerPtr controlSampler_
Control sampler.
Definition: SST.h:259
SST(const SpaceInformationPtr &si)
Constructor.
Definition: SST.cpp:46
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition: Planner.h:418
virtual void sampleGoal(State *st) const =0
Sample a state in the goal region.
double pruningRadius_
The radius for determining the size of the pruning region.
Definition: SST.h:278
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: SST.h:250
double uniform01()
Generate a random real between 0 and 1.
Definition: RandomNumbers.h:68
base::OptimizationObjectivePtr opt_
The optimization objective.
Definition: SST.h:292
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:58
Invalid start state or no start state specified.
Definition: PlannerStatus.h:56
double getSelectionRadius() const
Get the selection radius the planner is using.
Definition: SST.h:111
Motion * rep_
The node in the tree that is within the pruning radius.
Definition: SST.h:237
Abstract definition of a goal region that can be sampled.
void copyControl(Control *destination, const Control *source) const
Copy a control to another.
void setPruningRadius(double pruningRadius)
Set the radius for pruning nodes.
Definition: SST.h:126
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
Motion * selectNode(Motion *sample)
Finds the best node in the tree withing the selection radius around a random sample.
Definition: SST.cpp:160
double selectionRadius_
The radius for determining the node selected for extension.
Definition: SST.h:275
bool canSample() const
Return true if maxSampleCount() > 0, since in this case samples can certainly be produced.
unsigned int getMaxControlDuration() const
Get the maximum number of steps a control is propagated for.
Control * cloneControl(const Control *source) const
Clone a control.
unsigned int steps_
The number of steps_ the control is applied for.
Definition: SST.h:200
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: SST.cpp:69
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 class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
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 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
A shared pointer wrapper for ompl::control::SpaceInformation.
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
base::State * state_
The state contained by the motion.
Definition: SST.h:194
std::shared_ptr< NearestNeighbors< Motion * > > witnesses_
A nearest-neighbors datastructure containing the tree of witness motions.
Definition: SST.h:268
virtual bool hasControls() const
Indicate whether any information about controls (ompl::control::Control) is stored in this instance...
RNG rng_
The random number generator.
Definition: SST.h:281
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:405
const std::string & getName() const
Get the name of the planner.
Definition: Planner.cpp:56
double getPruningRadius() const
Get the pruning radius the planner is using.
Definition: SST.h:132
void freeControl(Control *control) const
Free the memory of a control.
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:415
Representation of a motion.
Definition: SST.h:154
void setGoalBias(double goalBias)
Definition: SST.h:86
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Continue solving for some amount of time. Return true if solution was found.
Definition: SST.cpp:213
int uniformInt(int lower_bound, int upper_bound)
Generate a random integer within given bounds: [lower_bound, upper_bound].
Definition: RandomNumbers.h:81
void freeMemory()
Free the memory allocated by this planner.
Definition: SST.cpp:121
void setSelectionRadius(double selectionRadius)
Set the radius for selecting nodes relative to random sample.
Definition: SST.h:105
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:47
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:272
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68