Loading...
Searching...
No Matches
LBTRRT.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, Tel Aviv University
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 the Tel Aviv 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/* Author: Oren Salzman, Aditya Mandalika, Sertac Karaman, Ioan Sucan, Mark Moll */
36
37#include "ompl/geometric/planners/rrt/LBTRRT.h"
38#include "ompl/base/goals/GoalSampleableRegion.h"
39#include "ompl/tools/config/SelfConfig.h"
40#include <limits>
41#include <cmath>
42#include <boost/math/constants/constants.hpp>
43
44ompl::geometric::LBTRRT::LBTRRT(const base::SpaceInformationPtr &si) : base::Planner(si, "LBTRRT")
45{
46 specs_.approximateSolutions = true;
47 specs_.directed = true;
48
49 Planner::declareParam<double>("range", this, &LBTRRT::setRange, &LBTRRT::getRange, "0.:1.:10000.");
50 Planner::declareParam<double>("goal_bias", this, &LBTRRT::setGoalBias, &LBTRRT::getGoalBias, "0.:.05:1.");
51 Planner::declareParam<double>("epsilon", this, &LBTRRT::setApproximationFactor, &LBTRRT::getApproximationFactor,
52 "0.:.1:10.");
53
54 addPlannerProgressProperty("iterations INTEGER", [this] { return getIterationCount(); });
55 addPlannerProgressProperty("best cost REAL", [this] { return getBestCost(); });
56}
57
58ompl::geometric::LBTRRT::~LBTRRT()
59{
60 freeMemory();
61}
62
64{
65 Planner::clear();
66 sampler_.reset();
67 freeMemory();
68 if (nn_)
69 nn_->clear();
70 lowerBoundGraph_.clear();
71 lastGoalMotion_ = nullptr;
72
73 iterations_ = 0;
74 bestCost_ = std::numeric_limits<double>::infinity();
75}
76
78{
79 Planner::setup();
82
83 if (!nn_)
85 nn_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
86}
87
89{
90 if (!idToMotionMap_.empty())
91 {
92 for (auto &i : idToMotionMap_)
93 {
94 if (i->state_ != nullptr)
95 si_->freeState(i->state_);
96 delete i;
97 }
98 }
99 idToMotionMap_.clear();
100}
101
103{
105 // update goal and check validity
106 base::Goal *goal = pdef_->getGoal().get();
107 auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
108
109 if (goal == nullptr)
110 {
111 OMPL_ERROR("%s: Goal undefined", getName().c_str());
113 }
114
115 // update start and check validity
116 while (const base::State *st = pis_.nextStart())
117 {
118 auto *motion = new Motion(si_);
119 si_->copyState(motion->state_, st);
120 motion->id_ = nn_->size();
121 idToMotionMap_.push_back(motion);
122 nn_->add(motion);
123 lowerBoundGraph_.addVertex(motion->id_);
124 }
125
126 if (nn_->size() == 0)
127 {
128 OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
130 }
131
132 if (nn_->size() > 1)
133 {
134 OMPL_ERROR("%s: There are multiple start states - currently not supported!", getName().c_str());
136 }
137
138 if (!sampler_)
139 sampler_ = si_->allocStateSampler();
140
141 OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
142
143 Motion *solution = lastGoalMotion_;
144 Motion *approxSol = nullptr;
145 double approxdif = std::numeric_limits<double>::infinity();
146 // e*(1+1/d) K-nearest constant, as used in RRT*
147 double k_rrg =
148 boost::math::constants::e<double>() + boost::math::constants::e<double>() / (double)si_->getStateDimension();
149
150 auto *rmotion = new Motion(si_);
151 base::State *rstate = rmotion->state_;
152 base::State *xstate = si_->allocState();
153 unsigned int statesGenerated = 0;
154
155 bestCost_ = lastGoalMotion_ != nullptr ? lastGoalMotion_->costApx_ : std::numeric_limits<double>::infinity();
156 while (!ptc())
157 {
158 iterations_++;
159 /* sample random state (with goal biasing) */
160 if ((goal_s != nullptr) && rng_.uniform01() < goalBias_ && goal_s->canSample())
161 goal_s->sampleGoal(rstate);
162 else
163 sampler_->sampleUniform(rstate);
164
165 /* find closest state in the tree */
166 Motion *nmotion = nn_->nearest(rmotion);
167 base::State *dstate = rstate;
168
169 /* find state to add */
170 double d = si_->distance(nmotion->state_, rstate);
171 if (d == 0) // this takes care of the case that the goal is a single point and we re-sample it multiple times
172 continue;
173 if (d > maxDistance_)
174 {
175 si_->getStateSpace()->interpolate(nmotion->state_, rstate, maxDistance_ / d, xstate);
176 dstate = xstate;
177 }
178
179 if (checkMotion(nmotion->state_, dstate))
180 {
181 statesGenerated++;
182 /* create a motion */
183 auto *motion = new Motion(si_);
184 si_->copyState(motion->state_, dstate);
185
186 /* update fields */
187 double distN = distanceFunction(nmotion, motion);
188
189 motion->id_ = nn_->size();
190 idToMotionMap_.push_back(motion);
191 lowerBoundGraph_.addVertex(motion->id_);
192 motion->parentApx_ = nmotion;
193
194 std::list<std::size_t> dummy;
195 lowerBoundGraph_.addEdge(nmotion->id_, motion->id_, distN, false, dummy);
196
197 motion->costLb_ = nmotion->costLb_ + distN;
198 motion->costApx_ = nmotion->costApx_ + distN;
199 nmotion->childrenApx_.push_back(motion);
200
201 std::vector<Motion *> nnVec;
202 unsigned int k = std::ceil(k_rrg * log((double)(nn_->size() + 1)));
203 nn_->nearestK(motion, k, nnVec);
204 nn_->add(motion); // if we add the motion before the nearestK call, we will get ourselves...
205
206 IsLessThan isLessThan(this, motion);
207 std::sort(nnVec.begin(), nnVec.end(), isLessThan);
208
209 //-------------------------------------------------//
210 // Rewiring Part (i) - find best parent of motion //
211 //-------------------------------------------------//
212 if (motion->parentApx_ != nnVec.front())
213 {
214 for (auto potentialParent : nnVec)
215 {
216 double dist = distanceFunction(potentialParent, motion);
217 considerEdge(potentialParent, motion, dist);
218 }
219 }
220
221 //------------------------------------------------------------------//
222 // Rewiring Part (ii) //
223 // check if motion may be a better parent to one of its neighbors //
224 //------------------------------------------------------------------//
225 for (auto child : nnVec)
226 {
227 double dist = distanceFunction(motion, child);
228 considerEdge(motion, child, dist);
229 }
230
231 double dist = 0.0;
232 bool sat = goal->isSatisfied(motion->state_, &dist);
233
234 if (sat)
235 {
236 approxdif = dist;
237 solution = motion;
238 }
239 if (dist < approxdif)
240 {
241 approxdif = dist;
242 approxSol = motion;
243 }
244
245 if (solution != nullptr && bestCost_ != solution->costApx_)
246 {
247 OMPL_INFORM("%s: approximation cost = %g", getName().c_str(), solution->costApx_);
248 bestCost_ = solution->costApx_;
249 }
250 }
251 }
252
253 bool solved = false;
254 bool approximate = false;
255
256 if (solution == nullptr)
257 {
258 solution = approxSol;
259 approximate = true;
260 }
261
262 if (solution != nullptr)
263 {
264 lastGoalMotion_ = solution;
265
266 /* construct the solution path */
267 std::vector<Motion *> mpath;
268 while (solution != nullptr)
269 {
270 mpath.push_back(solution);
271 solution = solution->parentApx_;
272 }
273
274 /* set the solution path */
275 auto path(std::make_shared<PathGeometric>(si_));
276 for (int i = mpath.size() - 1; i >= 0; --i)
277 path->append(mpath[i]->state_);
278 // Add the solution path.
279 base::PlannerSolution psol(path);
280 psol.setPlannerName(getName());
281 if (approximate)
282 psol.setApproximate(approxdif);
283 pdef_->addSolutionPath(psol);
284 solved = true;
285 }
286
287 si_->freeState(xstate);
288 if (rmotion->state_ != nullptr)
289 si_->freeState(rmotion->state_);
290 delete rmotion;
291
292 OMPL_INFORM("%s: Created %u states", getName().c_str(), statesGenerated);
293
294 return {solved, approximate};
295}
296
298{
299 // optimization - check if the bounded approximation invariant
300 // will be violated after the edge insertion (at least for the child node)
301 // if this is the case - perform the local planning
302 // this prevents the update of the graph due to the edge insertion and then the re-update as it is removed
303 double potential_cost = parent->costLb_ + c;
304 if (child->costApx_ > (1 + epsilon_) * potential_cost)
305 if (!checkMotion(parent, child))
306 return;
307
308 // update lowerBoundGraph_
309 std::list<std::size_t> affected;
310
311 lowerBoundGraph_.addEdge(parent->id_, child->id_, c, true, affected);
312
313 // now, check if the bounded apprimation invariant has been violated for each affected vertex
314 // insert them into a priority queue ordered according to the lb cost
315 std::list<std::size_t>::iterator iter;
316 IsLessThanLB isLessThanLB(this);
317 std::set<Motion *, IsLessThanLB> queue(isLessThanLB);
318
319 for (iter = affected.begin(); iter != affected.end(); ++iter)
320 {
321 Motion *m = getMotion(*iter);
322 m->costLb_ = lowerBoundGraph_.getShortestPathCost(*iter);
323 if (m->costApx_ > (1 + epsilon_) * m->costLb_)
324 queue.insert(m);
325 }
326
327 while (!queue.empty())
328 {
329 Motion *motion = *(queue.begin());
330 queue.erase(queue.begin());
331
332 if (motion->costApx_ > (1 + epsilon_) * motion->costLb_)
333 {
334 Motion *potential_parent = getMotion(lowerBoundGraph_.getShortestPathParent(motion->id_));
335 if (checkMotion(potential_parent, motion))
336 {
337 double delta = lazilyUpdateApxParent(motion, potential_parent);
338 updateChildCostsApx(motion, delta);
339 }
340 else
341 {
342 affected.clear();
343
344 lowerBoundGraph_.removeEdge(potential_parent->id_, motion->id_, true, affected);
345
346 for (iter = affected.begin(); iter != affected.end(); ++iter)
347 {
348 Motion *affected = getMotion(*iter);
349 auto lb_queue_iter = queue.find(affected);
350 if (lb_queue_iter != queue.end())
351 {
352 queue.erase(lb_queue_iter);
353 affected->costLb_ = lowerBoundGraph_.getShortestPathCost(affected->id_);
354 if (affected->costApx_ > (1 + epsilon_) * affected->costLb_)
355 queue.insert(affected);
356 }
357 else
358 {
359 affected->costLb_ = lowerBoundGraph_.getShortestPathCost(affected->id_);
360 }
361 }
362
363 motion->costLb_ = lowerBoundGraph_.getShortestPathCost(motion->id_);
364 if (motion->costApx_ > (1 + epsilon_) * motion->costLb_)
365 queue.insert(motion);
366
367 // optimization - we can remove the opposite edge
368 lowerBoundGraph_.removeEdge(motion->id_, potential_parent->id_, false, affected);
369 }
370 }
371 }
372}
373
375{
376 Planner::getPlannerData(data);
377
378 std::vector<Motion *> motions;
379 if (nn_)
380 nn_->list(motions);
381
382 if (lastGoalMotion_ != nullptr)
384
385 for (auto &motion : motions)
386 {
387 if (motion->parentApx_ == nullptr)
388 data.addStartVertex(base::PlannerDataVertex(motion->state_));
389 else
390 data.addEdge(base::PlannerDataVertex(motion->parentApx_->state_), base::PlannerDataVertex(motion->state_));
391 }
392}
393
395{
396 for (auto child : m->childrenApx_)
397 {
398 child->costApx_ += delta;
399 updateChildCostsApx(child, delta);
400 }
401}
402
404{
405 double dist = distanceFunction(parent, child);
406 removeFromParentApx(child);
407 double deltaApx = parent->costApx_ + dist - child->costApx_;
408 child->parentApx_ = parent;
409 parent->childrenApx_.push_back(child);
410 child->costApx_ = parent->costApx_ + dist;
411
412 return deltaApx;
413}
414
416{
417 std::vector<Motion *> &vec = m->parentApx_->childrenApx_;
418 for (auto it = vec.begin(); it != vec.end(); ++it)
419 if (*it == m)
420 {
421 vec.erase(it);
422 break;
423 }
424}
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.
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
Definition of an abstract state.
Definition State.h:50
Representation of a motion.
Definition LBTRRT.h:160
std::size_t id_
unique id of the motion
Definition LBTRRT.h:174
double costLb_
The lower bound cost of the motion while it is stored in the lowerBoundGraph_ and this may seem redun...
Definition LBTRRT.h:180
base::State * state_
The state contained by the motion.
Definition LBTRRT.h:172
Motion * parentApx_
The parent motion in the approximation tree.
Definition LBTRRT.h:182
double costApx_
The approximation cost.
Definition LBTRRT.h:184
std::vector< Motion * > childrenApx_
The children in the approximation tree.
Definition LBTRRT.h:186
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition LBTRRT.cpp:77
double getGoalBias() const
Get the goal bias the planner is using.
Definition LBTRRT.h:97
void removeFromParentApx(Motion *m)
remove motion from its parent in the approximation tree
Definition LBTRRT.cpp:415
DynamicSSSP lowerBoundGraph_
A graph of motions Glb.
Definition LBTRRT.h:269
void setApproximationFactor(double epsilon)
Set the apprimation factor.
Definition LBTRRT.h:132
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states).
Definition LBTRRT.h:240
double getRange() const
Get the range the planner is using.
Definition LBTRRT.h:113
unsigned int iterations_
Number of iterations the algorithm performed.
Definition LBTRRT.h:293
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition LBTRRT.h:266
double lazilyUpdateApxParent(Motion *child, Motion *parent)
lazily update the parent in the approximation tree without updating costs to cildren
Definition LBTRRT.cpp:403
void setRange(double distance)
Set the range the planner is supposed to use.
Definition LBTRRT.h:107
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 LBTRRT.cpp:374
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition LBTRRT.h:288
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition LBTRRT.h:276
double epsilon_
approximation factor
Definition LBTRRT.h:282
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition LBTRRT.cpp:102
RNG rng_
The random number generator.
Definition LBTRRT.h:285
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition LBTRRT.cpp:63
void freeMemory()
Free the memory allocated by this planner.
Definition LBTRRT.cpp:88
double bestCost_
Best cost found so far by algorithm.
Definition LBTRRT.h:295
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition LBTRRT.h:279
double getApproximationFactor() const
Get the apprimation factor.
Definition LBTRRT.h:138
void considerEdge(Motion *parent, Motion *child, double c)
consider an edge for addition to the roadmap
Definition LBTRRT.cpp:297
LBTRRT(const base::SpaceInformationPtr &si)
Constructor.
Definition LBTRRT.cpp:44
void setGoalBias(double goalBias)
Set the goal bias.
Definition LBTRRT.h:91
void updateChildCostsApx(Motion *m, double delta)
update the child cost of the approximation tree
Definition LBTRRT.cpp:394
bool checkMotion(const Motion *a, const Motion *b)
local planner
Definition LBTRRT.h:246
Motion * getMotion(std::size_t i)
get motion from id
Definition LBTRRT.h:257
base::StateSamplerPtr sampler_
State sampler.
Definition LBTRRT.h:263
std::vector< Motion * > idToMotionMap_
mapping between a motion id and the motion
Definition LBTRRT.h:272
This class contains methods that automatically configure various parameters for motion planning....
Definition SelfConfig.h:59
static NearestNeighbors< _T > * getDefaultNearestNeighbors(const base::Planner *planner)
Select a default nearest neighbor datastructure for the given space.
Definition SelfConfig.h:105
void configurePlannerRange(double &range)
Compute what a good length for motion segments is.
#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
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Representation of a solution to a planning problem.
void setApproximate(double difference)
Specify that the solution is approximate and set the difference to the goal.
void setPlannerName(const std::string &name)
Set the name of the planner used to compute this solution.
A class to store the exit status of Planner::solve().
@ INVALID_START
Invalid start state or no start state specified.
@ INVALID_GOAL
Invalid goal state.
comparator - metric is the lower bound cost
Definition LBTRRT.h:212
comparator - metric is the cost to reach state via a specific state
Definition LBTRRT.h:191