-
Notifications
You must be signed in to change notification settings - Fork 0
/
MARRTstar.cpp
617 lines (528 loc) · 22.3 KB
/
MARRTstar.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
#include "MARRTstar.h"
#include "ompl/base/goals/GoalSampleableRegion.h"
#include "ompl/tools/config/SelfConfig.h"
#include "ompl/base/objectives/PathLengthOptimizationObjective.h"
#include <algorithm>
#include <limits>
#include <map>
#include <queue>
#include <boost/math/constants/constants.hpp>
ompl::geometric::MaRRTstar::MaRRTstar(const base::SpaceInformationPtr &si) :
base::Planner(si, "MaRRTstar"),
goalBias_(0.05),
maxDistance_(0.0),
delayCC_(true),
lastGoalMotion_(NULL),
prune_(false),
pruneStatesThreshold_(0.95),
iterations_(0),
bestCost_(std::numeric_limits<double>::quiet_NaN())
{
specs_.approximateSolutions = true;
specs_.optimizingPaths = true;
specs_.canReportIntermediateSolutions = true;
Planner::declareParam<double>("range", this, &MaRRTstar::setRange, &MaRRTstar::getRange, "0.:1.:10000.");
Planner::declareParam<double>("goal_bias", this, &MaRRTstar::setGoalBias, &MaRRTstar::getGoalBias, "0.:.05:1.");
Planner::declareParam<bool>("delay_collision_checking", this, &MaRRTstar::setDelayCC, &MaRRTstar::getDelayCC, "0,1");
Planner::declareParam<bool>("prune", this, &MaRRTstar::setPrune, &MaRRTstar::getPrune, "0,1");
Planner::declareParam<double>("prune_states_threshold", this, &MaRRTstar::setPruneStatesImprovementThreshold, &MaRRTstar::getPruneStatesImprovementThreshold, "0.:.01:1.");
addPlannerProgressProperty("iterations INTEGER",
boost::bind(&MaRRTstar::getIterationCount, this));
addPlannerProgressProperty("best cost REAL",
boost::bind(&MaRRTstar::getBestCost, this));
}
ompl::geometric::MaRRTstar::~MaRRTstar()
{
freeMemory();
}
void ompl::geometric::MaRRTstar::setup()
{
Planner::setup();
tools::SelfConfig sc(si_, getName());
sc.configurePlannerRange(maxDistance_);
if (!si_->getStateSpace()->hasSymmetricDistance() || !si_->getStateSpace()->hasSymmetricInterpolate())
{
OMPL_WARN("%s requires a state space with symmetric distance and symmetric interpolation.", getName().c_str());
}
if (!nn_)
// nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion*>(si_->getStateSpace()));
nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion*>( (ompl::base::Planner*)this));
nn_->setDistanceFunction(boost::bind(&MaRRTstar::distanceFunction, this, _1, _2));
// Setup optimization objective
//
// If no optimization objective was specified, then default to
// optimizing path length as computed by the distance() function
// in the state space.
if (pdef_)
{
if (pdef_->hasOptimizationObjective())
opt_ = pdef_->getOptimizationObjective();
else
{
OMPL_INFORM("%s: No optimization objective specified. Defaulting to optimizing path length for the allowed planning time.", getName().c_str());
opt_.reset(new base::PathLengthOptimizationObjective(si_));
}
}
else
{
OMPL_INFORM("%s: problem definition is not set, deferring setup completion...", getName().c_str());
setup_ = false;
}
}
void ompl::geometric::MaRRTstar::clear()
{
Planner::clear();
sampler_.reset();
freeMemory();
if (nn_)
nn_->clear();
lastGoalMotion_ = NULL;
goalMotions_.clear();
iterations_ = 0;
bestCost_ = base::Cost(std::numeric_limits<double>::quiet_NaN());
}
ompl::base::PlannerStatus ompl::geometric::MaRRTstar::solve(const base::PlannerTerminationCondition &ptc)
{
checkValidity();
base::Goal *goal = pdef_->getGoal().get();
base::GoalSampleableRegion *goal_s = dynamic_cast<base::GoalSampleableRegion*>(goal);
bool symCost = opt_->isSymmetric();
while (const base::State *st = pis_.nextStart())
{
Motion *motion = new Motion(si_);
si_->copyState(motion->state, st);
motion->cost = opt_->identityCost();
nn_->add(motion);
startMotion_ = motion;
}
if (nn_->size() == 0)
{
OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
return base::PlannerStatus::INVALID_START;
}
if (!sampler_)
sampler_ = si_->allocStateSampler();
OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
if (prune_ && !si_->getStateSpace()->isMetricSpace())
OMPL_WARN("%s: tree pruning was activated but since the state space %s is not a metric space, "
"the optimization objective might not satisfy the triangle inequality. You may need to disable pruning."
, getName().c_str(), si_->getStateSpace()->getName().c_str());
const base::ReportIntermediateSolutionFn intermediateSolutionCallback = pdef_->getIntermediateSolutionCallback();
Motion *solution = lastGoalMotion_;
// \TODO Make this variable unnecessary, or at least have it
// persist across solve runs
base::Cost bestCost = opt_->infiniteCost();
bestCost_ = opt_->infiniteCost();
Motion *approximation = NULL;
double approximatedist = std::numeric_limits<double>::infinity();
bool sufficientlyShort = false;
Motion *rmotion = new Motion(si_);
base::State *rstate = rmotion->state;
base::State *xstate = si_->allocState();
// e+e/d. K-nearest RRT*
double k_rrg = boost::math::constants::e<double>() +
(boost::math::constants::e<double>() / (double)si_->getStateSpace()->getDimension());
std::vector<Motion*> nbh;
std::vector<base::Cost> costs;
std::vector<base::Cost> incCosts;
std::vector<std::size_t> sortedCostIndices;
std::vector<int> valid;
unsigned int rewireTest = 0;
unsigned int statesGenerated = 0;
if (solution)
OMPL_INFORM("%s: Starting planning with existing solution of cost %.5f", getName().c_str(), solution->cost.value());
OMPL_INFORM("%s: Initial k-nearest value of %u", getName().c_str(), (unsigned int)std::ceil(k_rrg * log((double)(nn_->size() + 1))));
// our functor for sorting nearest neighbors
CostIndexCompare compareFn(costs, *opt_);
while (ptc == false)
{
iterations_++;
// sample random state (with goal biasing)
// Goal samples are only sampled until maxSampleCount() goals are in the tree, to prohibit duplicate goal states.
if (goal_s && goalMotions_.size() < goal_s->maxSampleCount() && rng_.uniform01() < goalBias_ && goal_s->canSample())
goal_s->sampleGoal(rstate);
else
{
sampler_->sampleUniform(rstate);
if (prune_ && opt_->isCostBetterThan(bestCost_, costToGo(rmotion)))
continue;
}
// find closest state in the tree
Motion *nmotion = nn_->nearest(rmotion);
if (intermediateSolutionCallback && si_->equalStates(nmotion->state, rstate))
continue;
base::State *dstate = rstate;
// find state to add to the tree
double d = si_->distance(nmotion->state, rstate);
if (d > maxDistance_)
{
si_->getStateSpace()->interpolate(nmotion->state, rstate, maxDistance_ / d, xstate);
dstate = xstate;
}
// Check if the motion between the nearest state and the state to add is valid
if (si_->checkMotion(nmotion->state, dstate))
{
// create a motion
Motion *motion = new Motion(si_);
si_->copyState(motion->state, dstate);
motion->parent = nmotion;
motion->incCost = opt_->motionCost(nmotion->state, motion->state);
motion->cost = opt_->combineCosts(nmotion->cost, motion->incCost);
// Find nearby neighbors of the new motion - k-nearest RRT*
unsigned int k = std::ceil(k_rrg * log((double)(nn_->size() + 1)));
nn_->nearestK(motion, k, nbh);
rewireTest += nbh.size();
statesGenerated++;
// cache for distance computations
//
// Our cost caches only increase in size, so they're only
// resized if they can't fit the current neighborhood
if (costs.size() < nbh.size())
{
costs.resize(nbh.size());
incCosts.resize(nbh.size());
sortedCostIndices.resize(nbh.size());
}
// cache for motion validity (only useful in a symmetric space)
//
// Our validity caches only increase in size, so they're
// only resized if they can't fit the current neighborhood
if (valid.size() < nbh.size())
valid.resize(nbh.size());
std::fill(valid.begin(), valid.begin() + nbh.size(), 0);
// Finding the nearest neighbor to connect to
// By default, neighborhood states are sorted by cost, and collision checking
// is performed in increasing order of cost
if (delayCC_)
{
// calculate all costs and distances
for (std::size_t i = 0 ; i < nbh.size(); ++i)
{
incCosts[i] = opt_->motionCost(nbh[i]->state, motion->state);
costs[i] = opt_->combineCosts(nbh[i]->cost, incCosts[i]);
}
// sort the nodes
//
// we're using index-value pairs so that we can get at
// original, unsorted indices
for (std::size_t i = 0; i < nbh.size(); ++i)
sortedCostIndices[i] = i;
std::sort(sortedCostIndices.begin(), sortedCostIndices.begin() + nbh.size(),
compareFn);
// collision check until a valid motion is found
//
// ASYMMETRIC CASE: it's possible that none of these
// neighbors are valid. This is fine, because motion
// already has a connection to the tree through
// nmotion (with populated cost fields!).
for (std::vector<std::size_t>::const_iterator i = sortedCostIndices.begin();
i != sortedCostIndices.begin() + nbh.size();
++i)
{
if (nbh[*i] == nmotion || si_->checkMotion(nbh[*i]->state, motion->state))
{
motion->incCost = incCosts[*i];
motion->cost = costs[*i];
motion->parent = nbh[*i];
valid[*i] = 1;
break;
}
else valid[*i] = -1;
}
}
else // if not delayCC
{
motion->incCost = opt_->motionCost(nmotion->state, motion->state);
motion->cost = opt_->combineCosts(nmotion->cost, motion->incCost);
// find which one we connect the new state to
for (std::size_t i = 0 ; i < nbh.size(); ++i)
{
if (nbh[i] != nmotion)
{
incCosts[i] = opt_->motionCost(nbh[i]->state, motion->state);
costs[i] = opt_->combineCosts(nbh[i]->cost, incCosts[i]);
if (opt_->isCostBetterThan(costs[i], motion->cost))
{
if (si_->checkMotion(nbh[i]->state, motion->state))
{
motion->incCost = incCosts[i];
motion->cost = costs[i];
motion->parent = nbh[i];
valid[i] = 1;
}
else valid[i] = -1;
}
}
else
{
incCosts[i] = motion->incCost;
costs[i] = motion->cost;
valid[i] = 1;
}
}
}
if (prune_)
{
if (opt_->isCostBetterThan(costToGo(motion, false), bestCost_))
{
nn_->add(motion);
motion->parent->children.push_back(motion);
}
else // If the new motion does not improve the best cost it is ignored.
{
--statesGenerated;
si_->freeState(motion->state);
delete motion;
continue;
}
}
else
{
// add motion to the tree
nn_->add(motion);
motion->parent->children.push_back(motion);
}
bool checkForSolution = false;
for (std::size_t i = 0; i < nbh.size(); ++i)
{
if (nbh[i] != motion->parent)
{
base::Cost nbhIncCost;
if (symCost)
nbhIncCost = incCosts[i];
else
nbhIncCost = opt_->motionCost(motion->state, nbh[i]->state);
base::Cost nbhNewCost = opt_->combineCosts(motion->cost, nbhIncCost);
if (opt_->isCostBetterThan(nbhNewCost, nbh[i]->cost))
{
bool motionValid;
if (valid[i] == 0)
motionValid = si_->checkMotion(motion->state, nbh[i]->state);
else
motionValid = (valid[i] == 1);
if (motionValid)
{
// Remove this node from its parent list
removeFromParent (nbh[i]);
// Add this node to the new parent
nbh[i]->parent = motion;
nbh[i]->incCost = nbhIncCost;
nbh[i]->cost = nbhNewCost;
nbh[i]->parent->children.push_back(nbh[i]);
// Update the costs of the node's children
updateChildCosts(nbh[i]);
checkForSolution = true;
}
}
}
}
// Add the new motion to the goalMotion_ list, if it satisfies the goal
double distanceFromGoal;
if (goal->isSatisfied(motion->state, &distanceFromGoal))
{
goalMotions_.push_back(motion);
checkForSolution = true;
}
// Checking for solution or iterative improvement
if (checkForSolution)
{
bool updatedSolution = false;
for (size_t i = 0; i < goalMotions_.size(); ++i)
{
if (opt_->isCostBetterThan(goalMotions_[i]->cost, bestCost))
{
bestCost = goalMotions_[i]->cost;
bestCost_ = bestCost;
updatedSolution = true;
}
sufficientlyShort = opt_->isSatisfied(goalMotions_[i]->cost);
if (sufficientlyShort)
{
solution = goalMotions_[i];
break;
}
else if (!solution ||
opt_->isCostBetterThan(goalMotions_[i]->cost,solution->cost))
{
solution = goalMotions_[i];
updatedSolution = true;
}
}
if (updatedSolution)
{
if (prune_)
{
int n = pruneTree(bestCost_);
statesGenerated -= n;
}
if (intermediateSolutionCallback)
{
std::vector<const base::State *> spath;
Motion *intermediate_solution = solution->parent; // Do not include goal state to simplify code.
do
{
spath.push_back(intermediate_solution->state);
intermediate_solution = intermediate_solution->parent;
} while (intermediate_solution->parent != 0); // Do not include the start state.
intermediateSolutionCallback(this, spath, bestCost_);
}
}
}
// Checking for approximate solution (closest state found to the goal)
if (goalMotions_.size() == 0 && distanceFromGoal < approximatedist)
{
approximation = motion;
approximatedist = distanceFromGoal;
}
}
// terminate if a sufficient solution is found
if (solution && sufficientlyShort)
break;
}
bool approximate = (solution == NULL);
bool addedSolution = false;
if (approximate)
solution = approximation;
else
lastGoalMotion_ = solution;
if (solution != NULL)
{
ptc.terminate();
// construct the solution path
std::vector<Motion*> mpath;
while (solution != NULL)
{
mpath.push_back(solution);
solution = solution->parent;
}
// set the solution path
PathGeometric *geoPath = new PathGeometric(si_);
for (int i = mpath.size() - 1 ; i >= 0 ; --i)
geoPath->append(mpath[i]->state);
base::PathPtr path(geoPath);
// Add the solution path.
base::PlannerSolution psol(path);
psol.setPlannerName(getName());
if (approximate)
psol.setApproximate(approximatedist);
// Does the solution satisfy the optimization objective?
psol.setOptimized(opt_, bestCost, sufficientlyShort);
pdef_->addSolutionPath(psol);
addedSolution = true;
}
si_->freeState(xstate);
if (rmotion->state)
si_->freeState(rmotion->state);
delete rmotion;
OMPL_INFORM("%s: Created %u new states. Checked %u rewire options. %u goal states in tree.", getName().c_str(), statesGenerated, rewireTest, goalMotions_.size());
return base::PlannerStatus(addedSolution, approximate);
}
void ompl::geometric::MaRRTstar::removeFromParent(Motion *m)
{
for (std::vector<Motion*>::iterator it = m->parent->children.begin ();
it != m->parent->children.end (); ++it)
if (*it == m)
{
m->parent->children.erase(it);
break;
}
}
void ompl::geometric::MaRRTstar::updateChildCosts(Motion *m)
{
for (std::size_t i = 0; i < m->children.size(); ++i)
{
m->children[i]->cost = opt_->combineCosts(m->cost, m->children[i]->incCost);
updateChildCosts(m->children[i]);
}
}
void ompl::geometric::MaRRTstar::freeMemory()
{
if (nn_)
{
std::vector<Motion*> motions;
nn_->list(motions);
for (std::size_t i = 0 ; i < motions.size() ; ++i)
{
if (motions[i]->state)
si_->freeState(motions[i]->state);
delete motions[i];
}
}
}
void ompl::geometric::MaRRTstar::getPlannerData(base::PlannerData &data) const
{
Planner::getPlannerData(data);
std::vector<Motion*> motions;
if (nn_)
nn_->list(motions);
if (lastGoalMotion_)
data.addGoalVertex(base::PlannerDataVertex(lastGoalMotion_->state));
for (std::size_t i = 0 ; i < motions.size() ; ++i)
{
if (motions[i]->parent == NULL)
data.addStartVertex(base::PlannerDataVertex(motions[i]->state));
else
data.addEdge(base::PlannerDataVertex(motions[i]->parent->state),
base::PlannerDataVertex(motions[i]->state));
}
}
int ompl::geometric::MaRRTstar::pruneTree(const base::Cost pruneTreeCost)
{
const int tree_size = nn_->size();
pruneScratchSpace_.newTree.reserve(tree_size);
pruneScratchSpace_.newTree.clear();
pruneScratchSpace_.toBePruned.reserve(tree_size);
pruneScratchSpace_.toBePruned.clear();
pruneScratchSpace_.candidates.clear();
pruneScratchSpace_.candidates.push_back(startMotion_);
std::size_t j = 0;
while (j != pruneScratchSpace_.candidates.size())
{
Motion *candidate = pruneScratchSpace_.candidates[j++];
if (opt_->isCostBetterThan(pruneTreeCost, costToGo(candidate)))
pruneScratchSpace_.toBePruned.push_back(candidate);
else
{
pruneScratchSpace_.newTree.push_back(candidate);
pruneScratchSpace_.candidates.insert(pruneScratchSpace_.candidates.end(),
candidate->children.begin(), candidate->children.end());
}
}
// To create the new nn takes one order of magnitude in time more than just checking how many
// states would be pruned. Therefore, only prune if it removes a significant amount of states.
if ((double)pruneScratchSpace_.newTree.size() / tree_size < pruneStatesThreshold_)
{
for (std::size_t i = 0; i < pruneScratchSpace_.toBePruned.size(); ++i)
deleteBranch(pruneScratchSpace_.toBePruned[i]);
nn_->clear();
nn_->add(pruneScratchSpace_.newTree);
return (tree_size - pruneScratchSpace_.newTree.size());
}
return 0;
}
void ompl::geometric::MaRRTstar::deleteBranch(Motion *motion)
{
removeFromParent(motion);
std::vector<Motion *>& toDelete = pruneScratchSpace_.candidates;
toDelete.clear();
toDelete.push_back(motion);
while (!toDelete.empty())
{
Motion *mto_delete = toDelete.back();
toDelete.pop_back();
for(std::size_t i = 0; i < mto_delete->children.size(); ++i)
toDelete.push_back(mto_delete->children[i]);
si_->freeState(mto_delete->state);
delete mto_delete;
}
}
ompl::base::Cost ompl::geometric::MaRRTstar::costToGo(const Motion *motion, const bool shortest) const
{
base::Cost costToCome;
if (shortest)
costToCome = opt_->motionCost(startMotion_->state, motion->state); // h_s
else
costToCome = motion->cost; //d_s
const base::Cost costToGo = base::goalRegionCostToGo(motion->state, pdef_->getGoal().get()); // h_g
return opt_->combineCosts(costToCome, costToGo); // h_s + h_g
}