Loading...
Searching...
No Matches
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
45ompl::geometric::SST::SST(const base::SpaceInformationPtr &si) : base::Planner(si, "SST")
46{
47 specs_.approximateSolutions = true;
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,
54 "0.:.1:"
55 "100");
56 Planner::declareParam<double>("pruning_radius", this, &SST::setPruningRadius, &SST::getPruningRadius, "0.:.1:100");
57
58 addPlannerProgressProperty("best cost REAL", [this] { return std::to_string(this->prevSolutionCost_.value()); });
59}
60
61ompl::geometric::SST::~SST()
62{
63 freeMemory();
64}
65
67{
69 if (!nn_)
71 nn_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
72 if (!witnesses_)
74 witnesses_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
75
76 if (pdef_)
77 {
78 if (pdef_->hasOptimizationObjective())
79 {
80 opt_ = pdef_->getOptimizationObjective();
81 if (dynamic_cast<base::MaximizeMinClearanceObjective *>(opt_.get()) ||
82 dynamic_cast<base::MinimaxObjective *>(opt_.get()))
83 OMPL_WARN("%s: Asymptotic near-optimality has only been proven with Lipschitz continuous cost "
84 "functions w.r.t. state and control. This optimization objective will result in undefined "
85 "behavior",
86 getName().c_str());
87 }
88 else
89 {
90 OMPL_WARN("%s: No optimization object set. Using path length", getName().c_str());
91 opt_ = std::make_shared<base::PathLengthOptimizationObjective>(si_);
92 pdef_->setOptimizationObjective(opt_);
93 }
94 }
95 else
96 {
97 OMPL_WARN("%s: No optimization object set. Using path length", getName().c_str());
98 opt_ = std::make_shared<base::PathLengthOptimizationObjective>(si_);
99 }
100 prevSolutionCost_ = opt_->infiniteCost();
101}
102
104{
105 Planner::clear();
106 sampler_.reset();
107 freeMemory();
108 if (nn_)
109 nn_->clear();
110 if (witnesses_)
111 witnesses_->clear();
112 if (opt_)
113 prevSolutionCost_ = opt_->infiniteCost();
114}
115
117{
118 if (nn_)
119 {
120 std::vector<Motion *> motions;
121 nn_->list(motions);
122 for (auto &motion : motions)
123 {
124 if (motion->state_)
125 si_->freeState(motion->state_);
126 delete motion;
127 }
128 }
129 if (witnesses_)
130 {
131 std::vector<Motion *> witnesses;
132 witnesses_->list(witnesses);
133 for (auto &witness : witnesses)
134 {
135 if (witness->state_)
136 si_->freeState(witness->state_);
137 delete witness;
138 }
139 }
140
141 for (auto &i : prevSolution_)
142 {
143 if (i)
144 si_->freeState(i);
145 }
146 prevSolution_.clear();
147}
148
150{
151 std::vector<Motion *> ret;
152 Motion *selected = nullptr;
153 base::Cost bestCost = opt_->infiniteCost();
154 nn_->nearestR(sample, selectionRadius_, ret);
155 for (auto &i : ret)
156 {
157 if (!i->inactive_ && opt_->isCostBetterThan(i->accCost_, bestCost))
158 {
159 bestCost = i->accCost_;
160 selected = i;
161 }
162 }
163 if (selected == nullptr)
164 {
165 int k = 1;
166 while (selected == nullptr)
167 {
168 nn_->nearestK(sample, k, ret);
169 for (unsigned int i = 0; i < ret.size() && selected == nullptr; i++)
170 if (!ret[i]->inactive_)
171 selected = ret[i];
172 k += 5;
173 }
174 }
175 return selected;
176}
177
179{
180 if (witnesses_->size() > 0)
181 {
182 auto *closest = static_cast<Witness *>(witnesses_->nearest(node));
183 if (distanceFunction(closest, node) > pruningRadius_)
184 {
185 closest = new Witness(si_);
186 closest->linkRep(node);
187 si_->copyState(closest->state_, node->state_);
188 witnesses_->add(closest);
189 }
190 return closest;
191 }
192 else
193 {
194 auto *closest = new Witness(si_);
195 closest->linkRep(node);
196 si_->copyState(closest->state_, node->state_);
197 witnesses_->add(closest);
198 return closest;
199 }
200}
201
203{
204 // sample random point to serve as a direction
205 base::State *xstate = si_->allocState();
206 sampler_->sampleUniform(xstate);
207
208 // sample length of step from (0 - maxDistance_]
209 double step = rng_.uniformReal(0, maxDistance_);
210
211 // take a step of length step towards the random state
212 double d = si_->distance(m->state_, xstate);
213 si_->getStateSpace()->interpolate(m->state_, xstate, step / d, xstate);
214 si_->enforceBounds(xstate);
215
216 return xstate;
217}
218
220{
222 base::Goal *goal = pdef_->getGoal().get();
223 auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
224
225 while (const base::State *st = pis_.nextStart())
226 {
227 auto *motion = new Motion(si_);
228 si_->copyState(motion->state_, st);
229 nn_->add(motion);
230 motion->accCost_ = opt_->identityCost();
231 findClosestWitness(motion);
232 }
233
234 if (nn_->size() == 0)
235 {
236 OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
238 }
239
240 if (!sampler_)
241 sampler_ = si_->allocStateSampler();
242
243 const base::ReportIntermediateSolutionFn intermediateSolutionCallback = pdef_->getIntermediateSolutionCallback();
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 if (intermediateSolutionCallback)
330 {
331 // the callback requires a vector with const elements -> create a copy
332 std::vector<const base::State *> prevSolutionConst(prevSolution_.begin(), prevSolution_.end());
333 intermediateSolutionCallback(this, prevSolutionConst, prevSolutionCost_);
334 }
335 sufficientlyShort = opt_->isSatisfied(solution->accCost_);
336 if (sufficientlyShort)
337 {
338 break;
339 }
340 }
341 if (solution == nullptr && dist < approxdif)
342 {
343 approxdif = dist;
344 approxsol = motion;
345
346 for (auto &i : prevSolution_)
347 {
348 if (i)
349 si_->freeState(i);
350 }
351 prevSolution_.clear();
352 Motion *solTrav = approxsol;
353 while (solTrav != nullptr)
354 {
355 prevSolution_.push_back(si_->cloneState(solTrav->state_));
356 solTrav = solTrav->parent_;
357 }
358 }
359
360 if (oldRep != rmotion)
361 {
362 while (oldRep->inactive_ && oldRep->numChildren_ == 0)
363 {
364 oldRep->inactive_ = true;
365 nn_->remove(oldRep);
366
367 if (oldRep->state_)
368 si_->freeState(oldRep->state_);
369
370 oldRep->state_ = nullptr;
371 oldRep->parent_->numChildren_--;
372 Motion *oldRepParent = oldRep->parent_;
373 delete oldRep;
374 oldRep = oldRepParent;
375 }
376 }
377 }
378 }
379 iterations++;
380 }
381
382 bool solved = false;
383 bool approximate = false;
384 if (solution == nullptr)
385 {
386 solution = approxsol;
387 approximate = true;
388 }
389
390 if (solution != nullptr)
391 {
392 /* set the solution path */
393 auto path(std::make_shared<PathGeometric>(si_));
394 for (int i = prevSolution_.size() - 1; i >= 0; --i)
395 path->append(prevSolution_[i]);
396 solved = true;
397 pdef_->addSolutionPath(path, approximate, approxdif, getName());
398 }
399
400 si_->freeState(xstate);
401 if (rmotion->state_)
402 si_->freeState(rmotion->state_);
403 rmotion->state_ = nullptr;
404 delete rmotion;
405
406 OMPL_INFORM("%s: Created %u states in %u iterations", getName().c_str(), nn_->size(), iterations);
407
408 return {solved, approximate};
409}
410
412{
413 Planner::getPlannerData(data);
414
415 std::vector<Motion *> motions;
416 std::vector<Motion *> allMotions;
417 if (nn_)
418 nn_->list(motions);
419
420 for (auto &motion : motions)
421 if (motion->numChildren_ == 0)
422 allMotions.push_back(motion);
423 for (unsigned i = 0; i < allMotions.size(); i++)
424 if (allMotions[i]->getParent() != nullptr)
425 allMotions.push_back(allMotions[i]->getParent());
426
427 if (prevSolution_.size() != 0)
429
430 for (auto &allMotion : allMotions)
431 {
432 if (allMotion->getParent() == nullptr)
433 data.addStartVertex(base::PlannerDataVertex(allMotion->getState()));
434 else
435 data.addEdge(base::PlannerDataVertex(allMotion->getParent()->getState()),
436 base::PlannerDataVertex(allMotion->getState()));
437 }
438}
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
double value() const
The value of the cost.
Definition Cost.h:56
Abstract definition of a goal region that can be sampled.
Abstract definition of goals.
Definition Goal.h:63
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
Objective for attempting to maximize the minimum clearance along a path.
The cost of a path is defined as the worst state cost over the entire path. This objective attempts t...
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition PlannerData.h:59
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
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...
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...
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...
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
PlannerInputStates pis_
Utility class to extract valid input states.
Definition Planner.h:407
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:394
PlannerSpecs specs_
The specifications of the planner (its capabilities).
Definition Planner.h:413
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition Planner.h:404
const std::string & getName() const
Get the name of the planner.
Definition Planner.cpp:56
SpaceInformationPtr si_
The space information for which planning is done.
Definition Planner.h:401
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:106
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition Planner.cpp:92
Definition of an abstract state.
Definition State.h:50
Representation of a motion.
Definition SST.h:171
unsigned numChildren_
Number of children.
Definition SST.h:199
base::State * state_
The state contained by the motion.
Definition SST.h:193
Motion * parent_
The parent motion in the exploration tree.
Definition SST.h:196
bool inactive_
If inactive, this node is not considered for selection.
Definition SST.h:202
Motion * rep_
The node in the tree that is within the pruning radius.
Definition SST.h:228
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition SST.h:263
base::StateSamplerPtr sampler_
State sampler.
Definition SST.h:250
double getPruningRadius() const
Get the pruning radius the planner is using.
Definition SST.h:148
base::Cost prevSolutionCost_
The best solution cost we found so far.
Definition SST.h:278
Witness * findClosestWitness(Motion *node)
Find the closest witness node to a newly generated potential node.
Definition SST.cpp:178
double getSelectionRadius() const
Get the selection radius the planner is using.
Definition SST.h:127
void setPruningRadius(double pruningRadius)
Set the radius for pruning nodes.
Definition SST.h:142
void setGoalBias(double goalBias)
Definition SST.h:86
double getRange() const
Get the range the planner is using.
Definition SST.h:108
double getGoalBias() const
Get the goal bias the planner is using.
Definition SST.h:92
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition SST.cpp:66
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Continue solving for some amount of time. Return true if solution was found.
Definition SST.cpp:219
Motion * selectNode(Motion *sample)
Finds the best node in the tree withing the selection radius around a random sample.
Definition SST.cpp:149
void clear() override
Clear datastructures. Call this function if the input data to the planner has changed and you do not ...
Definition SST.cpp:103
base::OptimizationObjectivePtr opt_
The optimization objective.
Definition SST.h:281
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition SST.h:253
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:411
std::shared_ptr< NearestNeighbors< Motion * > > witnesses_
A nearest-neighbors datastructure containing the tree of witness motions.
Definition SST.h:256
RNG rng_
The random number generator.
Definition SST.h:272
void setSelectionRadius(double selectionRadius)
Set the radius for selecting nodes relative to random sample.
Definition SST.h:121
double selectionRadius_
The radius for determining the node selected for extension.
Definition SST.h:266
void freeMemory()
Free the memory allocated by this planner.
Definition SST.cpp:116
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:260
double pruningRadius_
The radius for determining the size of the pruning region.
Definition SST.h:269
SST(const base::SpaceInformationPtr &si)
Constructor.
Definition SST.cpp:45
std::vector< base::State * > prevSolution_
The best solution we found so far.
Definition SST.h:275
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states).
Definition SST.h:244
base::State * monteCarloProp(Motion *m)
Randomly propagate a new edge.
Definition SST.cpp:202
void setRange(double distance)
Set the range the planner is supposed to use.
Definition SST.h:102
static NearestNeighbors< _T > * getDefaultNearestNeighbors(const base::Planner *planner)
Select a default nearest neighbor datastructure for the given space.
Definition SelfConfig.h:105
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition Console.h:68
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition Console.h:64
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition Console.h:66
This namespace contains sampling based planning routines shared by both planning under geometric cons...
std::function< void(const Planner *, const std::vector< const base::State * > &, const Cost)> ReportIntermediateSolutionFn
When a planner has an intermediate solution (e.g., optimizing planners), a function with this signatu...
A class to store the exit status of Planner::solve().
@ INVALID_START
Invalid start state or no start state specified.