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  Planner::declareParam<double>("goal_bias", this, &SST::setGoalBias, &SST::getGoalBias, "0.:.05:1.");
55  Planner::declareParam<double>("selection_radius", this, &SST::setSelectionRadius, &SST::getSelectionRadius, "0.:.1:"
56  "100");
57  Planner::declareParam<double>("pruning_radius", this, &SST::setPruningRadius, &SST::getPruningRadius, "0.:.1:100");
58 }
59 
60 ompl::control::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  controlSampler_.reset();
109  freeMemory();
110  if (nn_)
111  nn_->clear();
112  if (witnesses_)
113  witnesses_->clear();
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  if (motion->control_)
128  siC_->freeControl(motion->control_);
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  delete witness;
139  }
140  }
141  for (auto &i : prevSolution_)
142  {
143  if (i)
144  si_->freeState(i);
145  }
146  prevSolution_.clear();
147  for (auto &prevSolutionControl : prevSolutionControls_)
148  {
149  if (prevSolutionControl)
150  siC_->freeControl(prevSolutionControl);
151  }
152  prevSolutionControls_.clear();
153  prevSolutionSteps_.clear();
154 }
155 
157 {
158  std::vector<Motion *> ret;
159  Motion *selected = nullptr;
160  base::Cost bestCost = opt_->infiniteCost();
161  nn_->nearestR(sample, selectionRadius_, ret);
162  for (auto &i : ret)
163  {
164  if (!i->inactive_ && opt_->isCostBetterThan(i->accCost_, bestCost))
165  {
166  bestCost = i->accCost_;
167  selected = i;
168  }
169  }
170  if (selected == nullptr)
171  {
172  int k = 1;
173  while (selected == nullptr)
174  {
175  nn_->nearestK(sample, k, ret);
176  for (unsigned int i = 0; i < ret.size() && selected == nullptr; i++)
177  if (!ret[i]->inactive_)
178  selected = ret[i];
179  k += 5;
180  }
181  }
182  return selected;
183 }
184 
186 {
187  if (witnesses_->size() > 0)
188  {
189  auto *closest = static_cast<Witness *>(witnesses_->nearest(node));
190  if (distanceFunction(closest, node) > pruningRadius_)
191  {
192  closest = new Witness(siC_);
193  closest->linkRep(node);
194  si_->copyState(closest->state_, node->state_);
195  witnesses_->add(closest);
196  }
197  return closest;
198  }
199  else
200  {
201  auto *closest = new Witness(siC_);
202  closest->linkRep(node);
203  si_->copyState(closest->state_, node->state_);
204  witnesses_->add(closest);
205  return closest;
206  }
207 }
208 
210 {
211  checkValidity();
212  base::Goal *goal = pdef_->getGoal().get();
213  auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
214 
215  while (const base::State *st = pis_.nextStart())
216  {
217  auto *motion = new Motion(siC_);
218  si_->copyState(motion->state_, st);
219  siC_->nullControl(motion->control_);
220  nn_->add(motion);
221  motion->accCost_ = opt_->identityCost();
222  findClosestWitness(motion);
223  }
224 
225  if (nn_->size() == 0)
226  {
227  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
229  }
230 
231  if (!sampler_)
232  sampler_ = si_->allocStateSampler();
233  if (!controlSampler_)
235 
236  OMPL_INFORM("%s: Starting planning with %u states already in datastructure\n", getName().c_str(), nn_->size());
237 
238  Motion *solution = nullptr;
239  Motion *approxsol = nullptr;
240  double approxdif = std::numeric_limits<double>::infinity();
241  bool sufficientlyShort = false;
242 
243  auto *rmotion = new Motion(siC_);
244  base::State *rstate = rmotion->state_;
245  Control *rctrl = rmotion->control_;
246  base::State *xstate = si_->allocState();
247 
248  unsigned iterations = 0;
249 
250  while (ptc == false)
251  {
252  /* sample random state (with goal biasing) */
253  if (goal_s && rng_.uniform01() < goalBias_ && goal_s->canSample())
254  goal_s->sampleGoal(rstate);
255  else
256  sampler_->sampleUniform(rstate);
257 
258  /* find closest state in the tree */
259  Motion *nmotion = selectNode(rmotion);
260 
261  /* sample a random control that attempts to go towards the random state, and also sample a control duration */
262  controlSampler_->sample(rctrl);
264  unsigned int propCd = siC_->propagateWhileValid(nmotion->state_, rctrl, cd, rstate);
265 
266  if (propCd == cd)
267  {
268  base::Cost incCost = opt_->motionCost(nmotion->state_, rstate);
269  base::Cost cost = opt_->combineCosts(nmotion->accCost_, incCost);
270  Witness *closestWitness = findClosestWitness(rmotion);
271 
272  if (closestWitness->rep_ == rmotion || opt_->isCostBetterThan(cost, closestWitness->rep_->accCost_))
273  {
274  Motion *oldRep = closestWitness->rep_;
275  /* create a motion */
276  auto *motion = new Motion(siC_);
277  motion->accCost_ = cost;
278  si_->copyState(motion->state_, rmotion->state_);
279  siC_->copyControl(motion->control_, rctrl);
280  motion->steps_ = cd;
281  motion->parent_ = nmotion;
282  nmotion->numChildren_++;
283  closestWitness->linkRep(motion);
284 
285  nn_->add(motion);
286  double dist = 0.0;
287  bool solv = goal->isSatisfied(motion->state_, &dist);
288  if (solv && opt_->isCostBetterThan(motion->accCost_, prevSolutionCost_))
289  {
290  approxdif = dist;
291  solution = motion;
292 
293  for (auto &i : prevSolution_)
294  if (i)
295  si_->freeState(i);
296  prevSolution_.clear();
297  for (auto &prevSolutionControl : prevSolutionControls_)
298  if (prevSolutionControl)
299  siC_->freeControl(prevSolutionControl);
300  prevSolutionControls_.clear();
301  prevSolutionSteps_.clear();
302 
303  Motion *solTrav = solution;
304  while (solTrav->parent_ != nullptr)
305  {
306  prevSolution_.push_back(si_->cloneState(solTrav->state_));
307  prevSolutionControls_.push_back(siC_->cloneControl(solTrav->control_));
308  prevSolutionSteps_.push_back(solTrav->steps_);
309  solTrav = solTrav->parent_;
310  }
311  prevSolution_.push_back(si_->cloneState(solTrav->state_));
312  prevSolutionCost_ = solution->accCost_;
313 
314  OMPL_INFORM("Found solution with cost %.2f", solution->accCost_.value());
315  sufficientlyShort = opt_->isSatisfied(solution->accCost_);
316  if (sufficientlyShort)
317  break;
318  }
319  if (solution == nullptr && dist < approxdif)
320  {
321  approxdif = dist;
322  approxsol = motion;
323 
324  for (auto &i : prevSolution_)
325  if (i)
326  si_->freeState(i);
327  prevSolution_.clear();
328  for (auto &prevSolutionControl : prevSolutionControls_)
329  if (prevSolutionControl)
330  siC_->freeControl(prevSolutionControl);
331  prevSolutionControls_.clear();
332  prevSolutionSteps_.clear();
333 
334  Motion *solTrav = approxsol;
335  while (solTrav->parent_ != nullptr)
336  {
337  prevSolution_.push_back(si_->cloneState(solTrav->state_));
338  prevSolutionControls_.push_back(siC_->cloneControl(solTrav->control_));
339  prevSolutionSteps_.push_back(solTrav->steps_);
340  solTrav = solTrav->parent_;
341  }
342  prevSolution_.push_back(si_->cloneState(solTrav->state_));
343  }
344 
345  if (oldRep != rmotion)
346  {
347  oldRep->inactive_ = true;
348  nn_->remove(oldRep);
349  while (oldRep->inactive_ && oldRep->numChildren_ == 0)
350  {
351  if (oldRep->state_)
352  si_->freeState(oldRep->state_);
353  if (oldRep->control_)
354  siC_->freeControl(oldRep->control_);
355 
356  oldRep->state_ = nullptr;
357  oldRep->control_ = 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<PathControl>(si_));
381  for (int i = prevSolution_.size() - 1; i >= 1; --i)
382  path->append(prevSolution_[i], prevSolutionControls_[i - 1],
383  prevSolutionSteps_[i - 1] * siC_->getPropagationStepSize());
384  path->append(prevSolution_[0]);
385  solved = true;
386  pdef_->addSolutionPath(path, approximate, approxdif, getName());
387  }
388 
389  si_->freeState(xstate);
390  if (rmotion->state_)
391  si_->freeState(rmotion->state_);
392  if (rmotion->control_)
393  siC_->freeControl(rmotion->control_);
394  delete rmotion;
395 
396  OMPL_INFORM("%s: Created %u states in %u iterations", getName().c_str(), nn_->size(), iterations);
397 
398  return base::PlannerStatus(solved, approximate);
399 }
400 
402 {
403  Planner::getPlannerData(data);
404 
405  std::vector<Motion *> motions;
406  std::vector<Motion *> allMotions;
407  if (nn_)
408  nn_->list(motions);
409 
410  for (auto &motion : motions)
411  {
412  if (motion->numChildren_ == 0)
413  {
414  allMotions.push_back(motion);
415  }
416  }
417  for (unsigned i = 0; i < allMotions.size(); i++)
418  {
419  if (allMotions[i]->parent_ != nullptr)
420  {
421  allMotions.push_back(allMotions[i]->parent_);
422  }
423  }
424 
425  double delta = siC_->getPropagationStepSize();
426 
427  if (prevSolution_.size() != 0)
429 
430  for (auto m : allMotions)
431  {
432  if (m->parent_)
433  {
434  if (data.hasControls())
435  data.addEdge(base::PlannerDataVertex(m->parent_->state_), base::PlannerDataVertex(m->state_),
436  control::PlannerDataEdgeControl(m->control_, m->steps_ * delta));
437  else
438  data.addEdge(base::PlannerDataVertex(m->parent_->state_), base::PlannerDataVertex(m->state_));
439  }
440  else
441  data.addStartVertex(base::PlannerDataVertex(m->state_));
442  }
443 }
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:203
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:104
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:248
unsigned numChildren_
Number of children.
Definition: SST.h:191
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:239
Definition of an abstract control.
Definition: Control.h:47
Motion * parent_
The parent motion in the exploration tree.
Definition: SST.h:188
std::vector< base::State * > prevSolution_
The best solution we found so far.
Definition: SST.h:267
base::Cost prevSolutionCost_
The best solution cost we found so far.
Definition: SST.h:272
Witness * findClosestWitness(Motion *node)
Find the closest witness node to a newly generated potential node.
Definition: SST.cpp:185
bool inactive_
If inactive, this node is not considered for selection.
Definition: SST.h:194
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:182
const SpaceInformation * siC_
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition: SST.h:245
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:242
SST(const SpaceInformationPtr &si)
Constructor.
Definition: SST.cpp:46
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition: Planner.h:409
double pruningRadius_
The radius for determining the size of the pruning region.
Definition: SST.h:261
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: SST.h:233
double uniform01()
Generate a random real between 0 and 1.
Definition: RandomNumbers.h:68
base::OptimizationObjectivePtr opt_
The optimization objective.
Definition: SST.h:275
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:220
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:156
double selectionRadius_
The radius for determining the node selected for extension.
Definition: SST.h:258
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:185
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: SST.cpp:65
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:412
A shared pointer wrapper for ompl::control::SpaceInformation.
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
base::State * state_
The state contained by the motion.
Definition: SST.h:179
std::shared_ptr< NearestNeighbors< Motion * > > witnesses_
A nearest-neighbors datastructure containing the tree of witness motions.
Definition: SST.h:251
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:264
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:401
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:406
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:209
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:117
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:255
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68