Loading...
Searching...
No Matches
LazyLBTRRT.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, Mark Moll */
36
37#include "ompl/geometric/planners/rrt/LazyLBTRRT.h"
38#include "ompl/tools/config/SelfConfig.h"
39#include <limits>
40#include <boost/foreach.hpp>
41#include <boost/math/constants/constants.hpp>
42
43namespace
44{
45 int getK(unsigned int n, double k_rrg)
46 {
47 return std::ceil(k_rrg * log((double)(n + 1)));
48 }
49} // namespace
50
51ompl::geometric::LazyLBTRRT::LazyLBTRRT(const base::SpaceInformationPtr &si) : base::Planner(si, "LazyLBTRRT")
52{
53 specs_.approximateSolutions = true;
54 specs_.directed = true;
55
56 Planner::declareParam<double>("range", this, &LazyLBTRRT::setRange, &LazyLBTRRT::getRange, "0.:1.:10000.");
57 Planner::declareParam<double>("goal_bias", this, &LazyLBTRRT::setGoalBias, &LazyLBTRRT::getGoalBias, "0.:.05:1.");
58 Planner::declareParam<double>("epsilon", this, &LazyLBTRRT::setApproximationFactor,
60
61 addPlannerProgressProperty("iterations INTEGER", [this] { return getIterationCount(); });
62 addPlannerProgressProperty("best cost REAL", [this] { return getBestCost(); });
63}
64
65ompl::geometric::LazyLBTRRT::~LazyLBTRRT()
66{
67 freeMemory();
68}
69
71{
72 Planner::clear();
73 sampler_.reset();
74 freeMemory();
75 if (nn_)
76 nn_->clear();
77 graphLb_.clear();
78 graphApx_.clear();
79 lastGoalMotion_ = nullptr;
80
81 iterations_ = 0;
82 bestCost_ = std::numeric_limits<double>::infinity();
83}
84
86{
87 Planner::setup();
90
91 if (!nn_)
93 nn_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
94}
95
97{
98 if (!idToMotionMap_.empty())
99 {
100 for (auto &i : idToMotionMap_)
101 {
102 if (i->state_ != nullptr)
103 si_->freeState(i->state_);
104 delete i;
105 }
106 idToMotionMap_.clear();
107 }
108 delete LPAstarApx_;
109 delete LPAstarLb_;
110}
111
113{
115 // update goal and check validity
116 base::Goal *goal = pdef_->getGoal().get();
117 auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
118
119 if (goal == nullptr || goal_s == nullptr)
120 {
121 OMPL_ERROR("%s: Unknown type of goal", getName().c_str());
123 }
124
125 if (!goal_s->couldSample())
126 {
127 OMPL_ERROR("%s: Insufficient states in sampleable goal region", getName().c_str());
129 }
130
131 while (const base::State *st = pis_.nextStart())
132 {
133 startMotion_ = createMotion(goal_s, st);
134 break;
135 }
136
137 if (nn_->size() == 0)
138 {
139 OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
141 }
142
143 if (!sampler_)
144 sampler_ = si_->allocStateSampler();
145
146 OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
147
148 bool solved = false;
149
150 auto *rmotion = new Motion(si_);
151 base::State *xstate = si_->allocState();
152
153 goalMotion_ = createGoalMotion(goal_s);
154
155 CostEstimatorLb costEstimatorLb(goal, idToMotionMap_);
156 LPAstarLb_ = new LPAstarLb(startMotion_->id_, goalMotion_->id_, graphLb_, costEstimatorLb); // rooted at source
157 CostEstimatorApx costEstimatorApx(this);
158 LPAstarApx_ = new LPAstarApx(goalMotion_->id_, startMotion_->id_, graphApx_, costEstimatorApx); // rooted at target
159 double approxdif = std::numeric_limits<double>::infinity();
160 // e+e/d. K-nearest RRT*
161 double k_rrg = boost::math::constants::e<double>() +
162 boost::math::constants::e<double>() / (double)si_->getStateSpace()->getDimension();
163
165 // step (1) - RRT
167 bestCost_ = std::numeric_limits<double>::infinity();
168 rrt(ptc, goal_s, xstate, rmotion, approxdif);
169 if (!ptc())
170 {
171 solved = true;
172
174 // step (2) - Lazy construction of G_lb
176 idToMotionMap_.push_back(goalMotion_);
177 int k = getK(idToMotionMap_.size(), k_rrg);
178 std::vector<Motion *> nnVec;
179 nnVec.reserve(k);
180 BOOST_FOREACH (Motion *motion, idToMotionMap_)
181 {
182 nn_->nearestK(motion, k, nnVec);
183 BOOST_FOREACH (Motion *neighbor, nnVec)
184 if (neighbor->id_ != motion->id_ && !edgeExistsLb(motion, neighbor))
185 addEdgeLb(motion, neighbor, distanceFunction(motion, neighbor));
186 }
187 idToMotionMap_.pop_back();
188 closeBounds(ptc);
189 }
190
192 // step (3) - anytime planning
194 while (!ptc())
195 {
196 std::tuple<Motion *, base::State *, double> res = rrtExtend(goal_s, xstate, rmotion, approxdif);
197 Motion *nmotion = std::get<0>(res);
198 base::State *dstate = std::get<1>(res);
199 double d = std::get<2>(res);
200
201 iterations_++;
202 if (dstate != nullptr)
203 {
204 /* create a motion */
205 Motion *motion = createMotion(goal_s, dstate);
206 addEdgeApx(nmotion, motion, d);
207 addEdgeLb(nmotion, motion, d);
208
209 int k = getK(nn_->size(), k_rrg);
210 std::vector<Motion *> nnVec;
211 nnVec.reserve(k);
212 nn_->nearestK(motion, k, nnVec);
213
214 BOOST_FOREACH (Motion *neighbor, nnVec)
215 if (neighbor->id_ != motion->id_ && !edgeExistsLb(motion, neighbor))
216 addEdgeLb(motion, neighbor, distanceFunction(motion, neighbor));
217
218 closeBounds(ptc);
219 }
220
221 std::list<std::size_t> pathApx;
222 double costApx = LPAstarApx_->computeShortestPath(pathApx);
223 if (bestCost_ > costApx)
224 {
225 OMPL_INFORM("%s: approximation cost = %g", getName().c_str(), costApx);
226 bestCost_ = costApx;
227 }
228 }
229
230 if (solved)
231 {
232 std::list<std::size_t> pathApx;
233 LPAstarApx_->computeShortestPath(pathApx);
234
235 /* set the solution path */
236 auto path(std::make_shared<PathGeometric>(si_));
237
238 // the path is in reverse order
239 for (auto rit = pathApx.rbegin(); rit != pathApx.rend(); ++rit)
240 path->append(idToMotionMap_[*rit]->state_);
241
242 pdef_->addSolutionPath(path, !solved, 0);
243 }
244
245 si_->freeState(xstate);
246 if (rmotion->state_ != nullptr)
247 si_->freeState(rmotion->state_);
248 delete rmotion;
249
250 OMPL_INFORM("%s: Created %u states", getName().c_str(), nn_->size());
251
252 return {solved, !solved};
253}
254
255std::tuple<ompl::geometric::LazyLBTRRT::Motion *, ompl::base::State *, double> ompl::geometric::LazyLBTRRT::rrtExtend(
256 const base::GoalSampleableRegion *goal_s, base::State *xstate, Motion *rmotion, double &approxdif)
257{
258 base::State *rstate = rmotion->state_;
259 sampleBiased(goal_s, rstate);
260 /* find closest state in the tree */
261 Motion *nmotion = nn_->nearest(rmotion);
262 base::State *dstate = rstate;
263
264 /* find state to add */
265 double d = distanceFunction(nmotion->state_, rstate);
266 if (d > maxDistance_)
267 {
268 si_->getStateSpace()->interpolate(nmotion->state_, rstate, maxDistance_ / d, xstate);
269 dstate = xstate;
270 d = maxDistance_;
271 }
272
273 if (!checkMotion(nmotion->state_, dstate))
274 return std::make_tuple((Motion *)nullptr, (base::State *)nullptr, 0.0);
275
276 // motion is valid
277 double dist = 0.0;
278 bool sat = goal_s->isSatisfied(dstate, &dist);
279 if (sat)
280 {
281 approxdif = dist;
282 }
283 if (dist < approxdif)
284 {
285 approxdif = dist;
286 }
287
288 return std::make_tuple(nmotion, dstate, d);
289}
290
291void ompl::geometric::LazyLBTRRT::rrt(const base::PlannerTerminationCondition &ptc, base::GoalSampleableRegion *goal_s,
292 base::State *xstate, Motion *rmotion, double &approxdif)
293{
294 while (!ptc())
295 {
296 std::tuple<Motion *, base::State *, double> res = rrtExtend(goal_s, xstate, rmotion, approxdif);
297 Motion *nmotion = std::get<0>(res);
298 base::State *dstate = std::get<1>(res);
299 double d = std::get<2>(res);
300
301 iterations_++;
302 if (dstate != nullptr)
303 {
304 /* create a motion */
305 Motion *motion = createMotion(goal_s, dstate);
306 addEdgeApx(nmotion, motion, d);
307
308 if (motion == goalMotion_)
309 return;
310 }
311 }
312}
313
315{
316 Planner::getPlannerData(data);
317
318 if (lastGoalMotion_ != nullptr)
320
321 for (unsigned int i = 0; i < idToMotionMap_.size(); ++i)
322 {
323 const base::State *parent = idToMotionMap_[i]->state_;
324 if (boost::in_degree(i, graphApx_) == 0)
326 if (boost::out_degree(i, graphApx_) == 0)
328 else
329 {
330 boost::graph_traits<BoostGraph>::out_edge_iterator ei, ei_end;
331 for (boost::tie(ei, ei_end) = boost::out_edges(i, graphApx_); ei != ei_end; ++ei)
332 {
333 std::size_t v = boost::target(*ei, graphApx_);
334 data.addEdge(base::PlannerDataVertex(idToMotionMap_[v]->state_), base::PlannerDataVertex(parent));
335 }
336 }
337 }
338}
339
341{
342 /* sample random state (with goal biasing) */
343 if ((goal_s != nullptr) && rng_.uniform01() < goalBias_ && goal_s->canSample())
344 goal_s->sampleGoal(rstate);
345 else
346 sampler_->sampleUniform(rstate);
347};
348
349ompl::geometric::LazyLBTRRT::Motion *ompl::geometric::LazyLBTRRT::createMotion(const base::GoalSampleableRegion *goal_s,
350 const base::State *st)
351{
352 if (goal_s->isSatisfied(st))
353 return goalMotion_;
354
355 auto *motion = new Motion(si_);
356 si_->copyState(motion->state_, st);
357 motion->id_ = idToMotionMap_.size();
358 nn_->add(motion);
359 idToMotionMap_.push_back(motion);
360 addVertex(motion);
361
362 return motion;
363}
364
366ompl::geometric::LazyLBTRRT::createGoalMotion(const base::GoalSampleableRegion *goal_s)
367{
368 ompl::base::State *gstate = si_->allocState();
369 goal_s->sampleGoal(gstate);
370
371 auto *motion = new Motion(si_);
372 motion->state_ = gstate;
373 motion->id_ = idToMotionMap_.size();
374 idToMotionMap_.push_back(motion);
375 addVertex(motion);
376
377 return motion;
378}
379
380void ompl::geometric::LazyLBTRRT::closeBounds(const base::PlannerTerminationCondition &ptc)
381{
382 std::list<std::size_t> pathApx;
383 double costApx = LPAstarApx_->computeShortestPath(pathApx);
384 std::list<std::size_t> pathLb;
385 double costLb = LPAstarLb_->computeShortestPath(pathLb);
386
387 while (costApx > (1. + epsilon_) * costLb)
388 {
389 if (ptc())
390 return;
391
392 auto pathLbIter = pathLb.end();
393 pathLbIter--;
394 std::size_t v = *pathLbIter;
395 pathLbIter--;
396 std::size_t u = *pathLbIter;
397
398 while (edgeExistsApx(u, v))
399 {
400 v = u;
401 --pathLbIter;
402 u = *pathLbIter;
403 }
404
405 Motion *motionU = idToMotionMap_[u];
406 Motion *motionV = idToMotionMap_[v];
407 if (checkMotion(motionU, motionV))
408 {
409 // note that we change the direction between u and v due to the diff in definition between Apx and LB
410 addEdgeApx(motionV, motionU,
411 distanceFunction(motionU, motionV)); // the distance here can be obtained from the LB graph
412 pathApx.clear();
413 costApx = LPAstarApx_->computeShortestPath(pathApx);
414 }
415 else // the edge (u,v) was not collision free
416 {
417 removeEdgeLb(motionU, motionV);
418 pathLb.clear();
419 costLb = LPAstarLb_->computeShortestPath(pathLb);
420 }
421 }
422}
bool isSatisfied(const State *st) const override
Equivalent to calling isSatisfied(const State *, double *) with a nullptr second argument.
Abstract definition of a goal region that can be sampled.
virtual void sampleGoal(State *st) const =0
Sample a state in the goal region.
bool canSample() const
Return true if maxSampleCount() > 0, since in this case samples can certainly be produced.
Abstract definition of goals.
Definition Goal.h:63
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 LazyLBTRRT.h:141
std::size_t id_
The id of the motion.
Definition LazyLBTRRT.h:153
RNG rng_
The random number generator.
Definition LazyLBTRRT.h:307
double getApproximationFactor() const
Get the apprimation factor.
Definition LazyLBTRRT.h:288
void setApproximationFactor(double epsilon)
Set the apprimation factor.
Definition LazyLBTRRT.h:122
void sampleBiased(const base::GoalSampleableRegion *goal_s, base::State *rstate)
sample with goal biasing
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition LazyLBTRRT.h:301
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition LazyLBTRRT.h:313
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
base::StateSamplerPtr sampler_
State sampler.
Definition LazyLBTRRT.h:294
double distanceFunction(const base::State *a, const base::State *b) const
Compute distance between motions (actually distance between contained states).
Definition LazyLBTRRT.h:217
double getRange() const
Get the range the planner is using.
Definition LazyLBTRRT.h:103
void setGoalBias(double goalBias)
Set the goal bias.
Definition LazyLBTRRT.h:81
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition LazyLBTRRT.h:304
double getGoalBias() const
Get the goal bias the planner is using.
Definition LazyLBTRRT.h:87
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition LazyLBTRRT.h:297
void getPlannerData(base::PlannerData &data) const override
Get information about the current run of the motion planner. Repeated calls to this function will upd...
void setRange(double distance)
Set the range the planner is supposed to use.
Definition LazyLBTRRT.h:97
void freeMemory()
Free the memory allocated by this planner.
unsigned int iterations_
Number of iterations the algorithm performed.
Definition LazyLBTRRT.h:326
double bestCost_
Best cost found so far by algorithm.
Definition LazyLBTRRT.h:328
LazyLBTRRT(const base::SpaceInformationPtr &si)
Constructor.
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...
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...
void log(const char *file, int line, LogLevel level, const char *m,...)
Root level logging function. This should not be invoked directly, but rather used via a logging macro...
Definition Console.cpp:120
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.
@ UNRECOGNIZED_GOAL_TYPE
The goal is of a type that a planner does not recognize.