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/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
46ompl::control::SST::SST(const SpaceInformationPtr &si) : base::Planner(si, "SST")
47{
48 specs_.approximateSolutions = true;
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,
56 "0.:.1:"
57 "100");
58 Planner::declareParam<double>("pruning_radius", this, &SST::setPruningRadius, &SST::getPruningRadius, "0.:.1:100");
59
60 addPlannerProgressProperty("best cost REAL", [this] { return std::to_string(this->prevSolutionCost_.value()); });
61}
62
63ompl::control::SST::~SST()
64{
65 freeMemory();
66}
67
69{
71 if (!nn_)
73 nn_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
74 if (!witnesses_)
76 witnesses_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
77
78 if (pdef_)
79 {
80 if (pdef_->hasOptimizationObjective())
81 {
82 opt_ = pdef_->getOptimizationObjective();
83 if (dynamic_cast<base::MaximizeMinClearanceObjective *>(opt_.get()) ||
84 dynamic_cast<base::MinimaxObjective *>(opt_.get()))
85 OMPL_WARN("%s: Asymptotic near-optimality has only been proven with Lipschitz continuous cost "
86 "functions w.r.t. state and control. This optimization objective will result in undefined "
87 "behavior",
88 getName().c_str());
89 }
90 else
91 {
92 OMPL_WARN("%s: No optimization object set. Using path length", getName().c_str());
93 opt_ = std::make_shared<base::PathLengthOptimizationObjective>(si_);
94 pdef_->setOptimizationObjective(opt_);
95 }
96 }
97
98 prevSolutionCost_ = opt_->infiniteCost();
99}
100
102{
103 Planner::clear();
104 sampler_.reset();
105 controlSampler_.reset();
106 freeMemory();
107 if (nn_)
108 nn_->clear();
109 if (witnesses_)
110 witnesses_->clear();
111 if (opt_)
112 prevSolutionCost_ = opt_->infiniteCost();
113}
114
116{
117 if (nn_)
118 {
119 std::vector<Motion *> motions;
120 nn_->list(motions);
121 for (auto &motion : motions)
122 {
123 if (motion->state_)
124 si_->freeState(motion->state_);
125 if (motion->control_)
126 siC_->freeControl(motion->control_);
127 delete motion;
128 }
129 }
130 if (witnesses_)
131 {
132 std::vector<Motion *> witnesses;
133 witnesses_->list(witnesses);
134 for (auto &witness : witnesses)
135 {
136 delete witness;
137 }
138 }
139 for (auto &i : prevSolution_)
140 {
141 if (i)
142 si_->freeState(i);
143 }
144 prevSolution_.clear();
145 for (auto &prevSolutionControl : prevSolutionControls_)
146 {
147 if (prevSolutionControl)
148 siC_->freeControl(prevSolutionControl);
149 }
150 prevSolutionControls_.clear();
151 prevSolutionSteps_.clear();
152}
153
155{
156 std::vector<Motion *> ret;
157 Motion *selected = nullptr;
158 base::Cost bestCost = opt_->infiniteCost();
159 nn_->nearestR(sample, selectionRadius_, ret);
160 for (auto &i : ret)
161 {
162 if (!i->inactive_ && opt_->isCostBetterThan(i->accCost_, bestCost))
163 {
164 bestCost = i->accCost_;
165 selected = i;
166 }
167 }
168 if (selected == nullptr)
169 {
170 int k = 1;
171 while (selected == nullptr)
172 {
173 nn_->nearestK(sample, k, ret);
174 for (unsigned int i = 0; i < ret.size() && selected == nullptr; i++)
175 if (!ret[i]->inactive_)
176 selected = ret[i];
177 k += 5;
178 }
179 }
180 return selected;
181}
182
184{
185 if (witnesses_->size() > 0)
186 {
187 auto *closest = static_cast<Witness *>(witnesses_->nearest(node));
188 if (distanceFunction(closest, node) > pruningRadius_)
189 {
190 closest = new Witness(siC_);
191 closest->linkRep(node);
192 si_->copyState(closest->state_, node->state_);
193 witnesses_->add(closest);
194 }
195 return closest;
196 }
197 else
198 {
199 auto *closest = new Witness(siC_);
200 closest->linkRep(node);
201 si_->copyState(closest->state_, node->state_);
202 witnesses_->add(closest);
203 return closest;
204 }
205}
206
208{
210 base::Goal *goal = pdef_->getGoal().get();
211 auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
212
213 while (const base::State *st = pis_.nextStart())
214 {
215 auto *motion = new Motion(siC_);
216 si_->copyState(motion->state_, st);
217 siC_->nullControl(motion->control_);
218 nn_->add(motion);
219 motion->accCost_ = opt_->identityCost();
220 findClosestWitness(motion);
221 }
222
223 if (nn_->size() == 0)
224 {
225 OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
227 }
228
229 if (!sampler_)
230 sampler_ = si_->allocStateSampler();
231 if (!controlSampler_)
232 controlSampler_ = siC_->allocControlSampler();
233
234 const base::ReportIntermediateSolutionFn intermediateSolutionCallback = pdef_->getIntermediateSolutionCallback();
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);
263 unsigned int cd = rng_.uniformInt(siC_->getMinControlDuration(), siC_->getMaxControlDuration());
264 unsigned int propCd = siC_->propagateWhileValid(nmotion->state_, rctrl, cd, rstate);
265
266 if (propCd == cd)
267 {
268 base::Cost incCostMotion = opt_->motionCost(nmotion->state_, rstate);
269 base::Cost incCostControl = opt_->controlCost(rctrl, cd);
270 base::Cost incCost = opt_->combineCosts(incCostMotion, incCostControl);
271 base::Cost cost = opt_->combineCosts(nmotion->accCost_, incCost);
272 Witness *closestWitness = findClosestWitness(rmotion);
273
274 if (closestWitness->rep_ == rmotion || opt_->isCostBetterThan(cost, closestWitness->rep_->accCost_))
275 {
276 Motion *oldRep = closestWitness->rep_;
277 /* create a motion */
278 auto *motion = new Motion(siC_);
279 motion->accCost_ = cost;
280 si_->copyState(motion->state_, rmotion->state_);
281 siC_->copyControl(motion->control_, rctrl);
282 motion->steps_ = cd;
283 motion->parent_ = nmotion;
284 nmotion->numChildren_++;
285 closestWitness->linkRep(motion);
286
287 nn_->add(motion);
288 double dist = 0.0;
289 bool solv = goal->isSatisfied(motion->state_, &dist);
290 if (solv && opt_->isCostBetterThan(motion->accCost_, prevSolutionCost_))
291 {
292 approxdif = dist;
293 solution = motion;
294
295 for (auto &i : prevSolution_)
296 if (i)
297 si_->freeState(i);
298 prevSolution_.clear();
299 for (auto &prevSolutionControl : prevSolutionControls_)
300 if (prevSolutionControl)
301 siC_->freeControl(prevSolutionControl);
302 prevSolutionControls_.clear();
303 prevSolutionSteps_.clear();
304
305 Motion *solTrav = solution;
306 while (solTrav->parent_ != nullptr)
307 {
308 prevSolution_.push_back(si_->cloneState(solTrav->state_));
309 prevSolutionControls_.push_back(siC_->cloneControl(solTrav->control_));
310 prevSolutionSteps_.push_back(solTrav->steps_);
311 solTrav = solTrav->parent_;
312 }
313 prevSolution_.push_back(si_->cloneState(solTrav->state_));
314 prevSolutionCost_ = solution->accCost_;
315
316 OMPL_INFORM("Found solution with cost %.2f", solution->accCost_.value());
317 if (intermediateSolutionCallback)
318 {
319 // the callback requires a vector with const elements -> create a copy
320 std::vector<const base::State *> prevSolutionConst(prevSolution_.begin(), prevSolution_.end());
321 intermediateSolutionCallback(this, prevSolutionConst, prevSolutionCost_);
322 }
323 sufficientlyShort = opt_->isSatisfied(solution->accCost_);
324 if (sufficientlyShort)
325 break;
326 }
327 if (solution == nullptr && dist < approxdif)
328 {
329 approxdif = dist;
330 approxsol = motion;
331
332 for (auto &i : prevSolution_)
333 if (i)
334 si_->freeState(i);
335 prevSolution_.clear();
336 for (auto &prevSolutionControl : prevSolutionControls_)
337 if (prevSolutionControl)
338 siC_->freeControl(prevSolutionControl);
339 prevSolutionControls_.clear();
340 prevSolutionSteps_.clear();
341
342 Motion *solTrav = approxsol;
343 while (solTrav->parent_ != nullptr)
344 {
345 prevSolution_.push_back(si_->cloneState(solTrav->state_));
346 prevSolutionControls_.push_back(siC_->cloneControl(solTrav->control_));
347 prevSolutionSteps_.push_back(solTrav->steps_);
348 solTrav = solTrav->parent_;
349 }
350 prevSolution_.push_back(si_->cloneState(solTrav->state_));
351 }
352
353 if (oldRep != rmotion)
354 {
355 while (oldRep->inactive_ && oldRep->numChildren_ == 0)
356 {
357 oldRep->inactive_ = true;
358 nn_->remove(oldRep);
359
360 if (oldRep->state_)
361 si_->freeState(oldRep->state_);
362 if (oldRep->control_)
363 siC_->freeControl(oldRep->control_);
364
365 oldRep->state_ = nullptr;
366 oldRep->control_ = nullptr;
367 oldRep->parent_->numChildren_--;
368 Motion *oldRepParent = oldRep->parent_;
369 delete oldRep;
370 oldRep = oldRepParent;
371 }
372 }
373 }
374 }
375 iterations++;
376 }
377
378 bool solved = false;
379 bool approximate = false;
380 if (solution == nullptr)
381 {
382 solution = approxsol;
383 approximate = true;
384 }
385
386 if (solution != nullptr)
387 {
388 /* set the solution path */
389 auto path(std::make_shared<PathControl>(si_));
390 for (int i = prevSolution_.size() - 1; i >= 1; --i)
391 path->append(prevSolution_[i], prevSolutionControls_[i - 1],
392 prevSolutionSteps_[i - 1] * siC_->getPropagationStepSize());
393 path->append(prevSolution_[0]);
394 solved = true;
395 pdef_->addSolutionPath(path, approximate, approxdif, getName());
396 }
397
398 si_->freeState(xstate);
399 if (rmotion->state_)
400 si_->freeState(rmotion->state_);
401 if (rmotion->control_)
402 siC_->freeControl(rmotion->control_);
403 delete rmotion;
404
405 OMPL_INFORM("%s: Created %u states in %u iterations", getName().c_str(), nn_->size(), iterations);
406
407 return {solved, approximate};
408}
409
411{
412 Planner::getPlannerData(data);
413
414 std::vector<Motion *> motions;
415 std::vector<Motion *> allMotions;
416 if (nn_)
417 nn_->list(motions);
418
419 for (auto &motion : motions)
420 {
421 if (motion->numChildren_ == 0)
422 {
423 allMotions.push_back(motion);
424 }
425 }
426 for (unsigned i = 0; i < allMotions.size(); i++)
427 {
428 if (allMotions[i]->parent_ != nullptr)
429 {
430 allMotions.push_back(allMotions[i]->parent_);
431 }
432 }
433
434 double delta = siC_->getPropagationStepSize();
435
436 if (prevSolution_.size() != 0)
438
439 for (auto m : allMotions)
440 {
441 if (m->parent_)
442 {
443 if (data.hasControls())
444 data.addEdge(base::PlannerDataVertex(m->parent_->state_), base::PlannerDataVertex(m->state_),
445 control::PlannerDataEdgeControl(m->control_, m->steps_ * delta));
446 else
447 data.addEdge(base::PlannerDataVertex(m->parent_->state_), base::PlannerDataVertex(m->state_));
448 }
449 else
451 }
452}
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...
virtual bool hasControls() const
Indicate whether any information about controls (ompl::control::Control) is stored in this instance.
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
A shared pointer wrapper for ompl::base::SpaceInformation.
Definition of an abstract state.
Definition State.h:50
Definition of an abstract control.
Definition Control.h:48
Representation of an edge in PlannerData for planning with controls. This structure encodes a specifi...
Definition PlannerData.h:61
Representation of a motion.
Definition SST.h:155
base::State * state_
The state contained by the motion.
Definition SST.h:178
unsigned numChildren_
Number of children.
Definition SST.h:190
Control * control_
The control contained by the motion.
Definition SST.h:181
unsigned int steps_
The number of steps_ the control is applied for.
Definition SST.h:184
Motion * parent_
The parent motion in the exploration tree.
Definition SST.h:187
bool inactive_
If inactive, this node is not considered for selection.
Definition SST.h:193
Motion * rep_
The node in the tree that is within the pruning radius.
Definition SST.h:219
ControlSamplerPtr controlSampler_
Control sampler.
Definition SST.h:241
void setGoalBias(double goalBias)
Definition SST.h:86
RNG rng_
The random number generator.
Definition SST.h:263
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:410
void setSelectionRadius(double selectionRadius)
Set the radius for selecting nodes relative to random sample.
Definition SST.h:105
base::StateSamplerPtr sampler_
State sampler.
Definition SST.h:238
SST(const SpaceInformationPtr &si)
Constructor.
Definition SST.cpp:46
double getGoalBias() const
Get the goal bias the planner is using.
Definition SST.h:92
void freeMemory()
Free the memory allocated by this planner.
Definition SST.cpp:115
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 selectionRadius_
The radius for determining the node selected for extension.
Definition SST.h:257
double pruningRadius_
The radius for determining the size of the pruning region.
Definition SST.h:260
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Continue solving for some amount of time. Return true if solution was found.
Definition SST.cpp:207
base::Cost prevSolutionCost_
The best solution cost we found so far.
Definition SST.h:271
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:254
const SpaceInformation * siC_
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition SST.h:244
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states).
Definition SST.h:232
Motion * selectNode(Motion *sample)
Finds the best node in the tree withing the selection radius around a random sample.
Definition SST.cpp:154
double getSelectionRadius() const
Get the selection radius the planner is using.
Definition SST.h:111
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition SST.h:247
base::OptimizationObjectivePtr opt_
The optimization objective.
Definition SST.h:274
std::shared_ptr< NearestNeighbors< Motion * > > witnesses_
A nearest-neighbors datastructure containing the tree of witness motions.
Definition SST.h:250
double getPruningRadius() const
Get the pruning radius the planner is using.
Definition SST.h:132
void setPruningRadius(double pruningRadius)
Set the radius for pruning nodes.
Definition SST.h:126
std::vector< base::State * > prevSolution_
The best solution we found so far.
Definition SST.h:266
void clear() override
Clear datastructures. Call this function if the input data to the planner has changed and you do not ...
Definition SST.cpp:101
Witness * findClosestWitness(Motion *node)
Find the closest witness node to a newly generated potential node.
Definition SST.cpp:183
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.