Loading...
Searching...
No Matches
BiTRRT.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, Rice 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 Rice 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: Ryan Luna */
36
37#include <limits>
38
39#include "ompl/geometric/planners/rrt/BiTRRT.h"
40#include "ompl/base/goals/GoalSampleableRegion.h"
41#include "ompl/base/objectives/MechanicalWorkOptimizationObjective.h"
42#include "ompl/tools/config/MagicConstants.h"
43#include "ompl/tools/config/SelfConfig.h"
44
45ompl::geometric::BiTRRT::BiTRRT(const base::SpaceInformationPtr &si) : base::Planner(si, "BiTRRT")
46{
47 specs_.approximateSolutions = false;
48 specs_.directed = true;
49
50 Planner::declareParam<double>("range", this, &BiTRRT::setRange, &BiTRRT::getRange, "0.:1.:10000.");
51
52 // BiTRRT Specific Variables
53 setTempChangeFactor(0.1); // how much to increase the temp each time
54
55 Planner::declareParam<double>("temp_change_factor", this, &BiTRRT::setTempChangeFactor,
56 &BiTRRT::getTempChangeFactor, "0.:.1:1.");
57 Planner::declareParam<double>("init_temperature", this, &BiTRRT::setInitTemperature, &BiTRRT::getInitTemperature);
58 Planner::declareParam<double>("frontier_threshold", this, &BiTRRT::setFrontierThreshold,
60 Planner::declareParam<double>("frontier_node_ratio", this, &BiTRRT::setFrontierNodeRatio,
62 Planner::declareParam<double>("cost_threshold", this, &BiTRRT::setCostThreshold, &BiTRRT::getCostThreshold);
63}
64
65ompl::geometric::BiTRRT::~BiTRRT()
66{
67 freeMemory();
68}
69
71{
72 std::vector<Motion *> motions;
73
74 if (tStart_)
75 {
76 tStart_->list(motions);
77 for (auto &motion : motions)
78 {
79 if (motion->state != nullptr)
80 si_->freeState(motion->state);
81 delete motion;
82 }
83 }
84
85 if (tGoal_)
86 {
87 tGoal_->list(motions);
88 for (auto &motion : motions)
89 {
90 if (motion->state != nullptr)
91 si_->freeState(motion->state);
92 delete motion;
93 }
94 }
95}
96
98{
99 Planner::clear();
100 freeMemory();
101 if (tStart_)
102 tStart_->clear();
103 if (tGoal_)
104 tGoal_->clear();
105 connectionPoint_ = std::make_pair<Motion *, Motion *>(nullptr, nullptr);
106
107 // TRRT specific variables
110 frontierCount_ = 1; // init to 1 to prevent division by zero error
111 if (opt_)
112 bestCost_ = worstCost_ = opt_->identityCost();
113}
114
116{
117 Planner::setup();
119
120 // Configuring the range of the planner
121 if (maxDistance_ < std::numeric_limits<double>::epsilon())
122 {
125 }
126
127 // Configuring nearest neighbors structures for the planning trees
128 if (!tStart_)
130 if (!tGoal_)
132 tStart_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
133 tGoal_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
134
135 // Setup the optimization objective, if it isn't specified
136 if (!pdef_ || !pdef_->hasOptimizationObjective())
137 {
138 OMPL_INFORM("%s: No optimization objective specified. Defaulting to mechanical work minimization.",
139 getName().c_str());
140 opt_ = std::make_shared<base::MechanicalWorkOptimizationObjective>(si_);
141 }
142 else
143 opt_ = pdef_->getOptimizationObjective();
144
145 // Set the threshold that decides if a new node is a frontier node or non-frontier node
146 if (frontierThreshold_ < std::numeric_limits<double>::epsilon())
147 {
148 frontierThreshold_ = si_->getMaximumExtent() * 0.01;
149 OMPL_DEBUG("%s: Frontier threshold detected to be %lf", getName().c_str(), frontierThreshold_);
150 }
151
152 // initialize TRRT specific variables
155 frontierCount_ = 1; // init to 1 to prevent division by zero error
156 bestCost_ = worstCost_ = opt_->identityCost();
157 connectionRange_ = 10.0 * si_->getStateSpace()->getLongestValidSegmentLength();
158}
159
161 Motion *parent)
162{
163 auto *motion = new Motion(si_);
164 si_->copyState(motion->state, state);
165 motion->cost = opt_->stateCost(motion->state);
166 motion->parent = parent;
167 motion->root = parent != nullptr ? parent->root : nullptr;
168
169 if (opt_->isCostBetterThan(motion->cost, bestCost_)) // motion->cost is better than the existing best
170 bestCost_ = motion->cost;
171 if (opt_->isCostBetterThan(worstCost_, motion->cost)) // motion->cost is worse than the existing worst
172 worstCost_ = motion->cost;
173
174 // Add start motion to the tree
175 tree->add(motion);
176 return motion;
177}
178
180{
181 // Disallow any cost that is not better than the cost threshold
182 if (!opt_->isCostBetterThan(motionCost, costThreshold_))
183 return false;
184
185 // Always accept if the cost is near or below zero
186 if (motionCost.value() < 1e-4)
187 return true;
188
189 double dCost = motionCost.value();
190 double transitionProbability = exp(-dCost / temp_);
191 if (transitionProbability > 0.5)
192 {
193 double costRange = worstCost_.value() - bestCost_.value();
194 if (fabs(costRange) > 1e-4) // Do not divide by zero
195 // Successful transition test. Decrease the temperature slightly
196 temp_ /= exp(dCost / (0.1 * costRange));
197
198 return true;
199 }
200
201 // The transition failed. Increase the temperature (slightly)
203 return false;
204}
205
207{
208 if (dist > frontierThreshold_) // Exploration
209 {
211 return true;
212 }
213 // Refinement
214 // Check the current ratio first before accepting it
216 return false;
217
219 return true;
220}
221
223 Motion *toMotion, Motion *&result)
224{
225 bool reach = true;
226
227 // Compute the state to extend toward
228 bool treeIsStart = (tree == tStart_);
229 double d =
230 (treeIsStart ? si_->distance(nearest->state, toMotion->state) : si_->distance(toMotion->state, nearest->state));
231 // Truncate the random state to be no more than maxDistance_ from nearest neighbor
232 if (d > maxDistance_)
233 {
234 if (tree == tStart_)
235 si_->getStateSpace()->interpolate(nearest->state, toMotion->state, maxDistance_ / d, toMotion->state);
236 else
237 si_->getStateSpace()->interpolate(toMotion->state, nearest->state, 1.0 - maxDistance_ / d, toMotion->state);
238 d = maxDistance_;
239 reach = false;
240 }
241
242 // Validating the motion
243 // If we are in the goal tree, we validate the motion in reverse
244 // si_->checkMotion assumes that the first argument is valid, so we must check this explicitly
245 // If the motion is valid, check the probabilistic transition test and the
246 // expansion control to ensure high quality nodes are added.
247 bool validMotion =
248 (tree == tStart_ ? si_->checkMotion(nearest->state, toMotion->state) :
249 si_->isValid(toMotion->state) && si_->checkMotion(toMotion->state, nearest->state)) &&
250 transitionTest(tree == tStart_ ? opt_->motionCost(nearest->state, toMotion->state) :
251 opt_->motionCost(toMotion->state, nearest->state)) &&
253
254 if (validMotion)
255 {
256 result = addMotion(toMotion->state, tree, nearest);
257 return reach ? SUCCESS : ADVANCED;
258 }
259
260 return FAILED;
261}
262
264 Motion *&result)
265{
266 // Nearest neighbor
267 Motion *nearest = tree->nearest(toMotion);
268 return extendTree(nearest, tree, toMotion, result);
269}
270
272{
273 // Get the nearest state to nmotion in tree (nmotion is NOT in tree)
274 Motion *nearest = tree->nearest(nmotion);
275 bool treeIsStart = tree == tStart_;
276 double dist =
277 (treeIsStart ? si_->distance(nearest->state, nmotion->state) : si_->distance(nmotion->state, nearest->state));
278
279 // Do not attempt a connection if the trees are far apart
280 if (dist > connectionRange_)
281 return false;
282
283 // Copy the resulting state into our scratch space
284 si_->copyState(xmotion->state, nmotion->state);
285
286 // Do not try to connect states directly. Must chop up the
287 // extension into segments, just in case one piece fails
288 // the transition test
289 GrowResult result;
290 Motion *next = nullptr;
291 do
292 {
293 // Extend tree from nearest toward xmotion
294 // Store the result into next
295 // This function MAY trash xmotion
296 result = extendTree(nearest, tree, xmotion, next);
297
298 if (result == ADVANCED)
299 {
300 nearest = next;
301
302 // xmotion may get trashed during extension, so we reload it here
303 si_->copyState(xmotion->state,
304 nmotion->state); // xmotion may get trashed during extension, so we reload it here
305 }
306 } while (result == ADVANCED);
307
308 // Successful connection
309 if (result == SUCCESS)
310 {
311 Motion *startMotion = treeIsStart ? next : nmotion;
312 Motion *goalMotion = treeIsStart ? nmotion : next;
313
314 // Make sure start-goal pair is valid
315 if (pdef_->getGoal()->isStartGoalPairValid(startMotion->root, goalMotion->root))
316 {
317 // Since we have connected, nmotion->state and next->state have the same value
318 // We need to check one of their parents to avoid a duplicate state in the solution path
319 // One of these must be true, since we do not ever attempt to connect start and goal directly.
320 if (startMotion->parent != nullptr)
321 startMotion = startMotion->parent;
322 else
323 goalMotion = goalMotion->parent;
324
325 connectionPoint_ = std::make_pair(startMotion, goalMotion);
326 return true;
327 }
328 }
329
330 return false;
331}
332
334{
335 // Basic error checking
337
338 // Goal information
339 base::Goal *goal = pdef_->getGoal().get();
340 auto *gsr = dynamic_cast<base::GoalSampleableRegion *>(goal);
341
342 if (gsr == nullptr)
343 {
344 OMPL_ERROR("%s: Goal object does not derive from GoalSampleableRegion", getName().c_str());
346 }
347
348 // Loop through the (valid) input states and add them to the start tree
349 while (const base::State *state = pis_.nextStart())
350 {
351 auto *motion = new Motion(si_);
352 si_->copyState(motion->state, state);
353 motion->cost = opt_->stateCost(motion->state);
354 motion->root = motion->state; // this state is the root of a tree
355
356 if (tStart_->size() == 0) // do not overwrite best/worst from a prior call to solve
357 worstCost_ = bestCost_ = motion->cost;
358
359 // Add start motion to the tree
360 tStart_->add(motion);
361 }
362
363 if (tStart_->size() == 0)
364 {
365 OMPL_ERROR("%s: Start tree has no valid states!", getName().c_str());
367 }
368
369 // Do the same for the goal tree, if it is empty, but only once
370 if (tGoal_->size() == 0)
371 {
372 const base::State *state = pis_.nextGoal(ptc);
373 if (state != nullptr)
374 {
375 Motion *motion = addMotion(state, tGoal_);
376 motion->root = motion->state; // this state is the root of a tree
377 }
378 }
379
380 if (tGoal_->size() == 0)
381 {
382 OMPL_ERROR("%s: Goal tree has no valid states!", getName().c_str());
384 }
385
386 OMPL_INFORM("%s: Planning started with %d states already in datastructure", getName().c_str(),
387 (int)(tStart_->size() + tGoal_->size()));
388
389 base::StateSamplerPtr sampler = si_->allocStateSampler();
390
391 auto *rmotion = new Motion(si_);
392 base::State *rstate = rmotion->state;
393
394 auto *xmotion = new Motion(si_);
395 base::State *xstate = xmotion->state;
396
397 TreeData tree = tStart_;
398 TreeData otherTree = tGoal_;
399
400 bool solved = false;
401 // Planning loop
402 while (!ptc)
403 {
404 // Check if there are more goal states
405 if (pis_.getSampledGoalsCount() < tGoal_->size() / 2)
406 {
407 if (const base::State *state = pis_.nextGoal())
408 {
409 Motion *motion = addMotion(state, tGoal_);
410 motion->root = motion->state; // this state is the root of a tree
411 }
412 }
413
414 // Sample a state uniformly at random
415 sampler->sampleUniform(rstate);
416
417 Motion *result; // the motion that gets added in extendTree
418 if (extendTree(rmotion, tree, result) != FAILED) // we added something new to the tree
419 {
420 // Try to connect the other tree to the node we just added
421 if (connectTrees(result, otherTree, xmotion))
422 {
423 // The trees have been connected. Construct the solution path
424 Motion *solution = connectionPoint_.first;
425 std::vector<Motion *> mpath1;
426 while (solution != nullptr)
427 {
428 mpath1.push_back(solution);
429 solution = solution->parent;
430 }
431
432 solution = connectionPoint_.second;
433 std::vector<Motion *> mpath2;
434 while (solution != nullptr)
435 {
436 mpath2.push_back(solution);
437 solution = solution->parent;
438 }
439
440 auto path(std::make_shared<PathGeometric>(si_));
441 path->getStates().reserve(mpath1.size() + mpath2.size());
442 for (int i = mpath1.size() - 1; i >= 0; --i)
443 path->append(mpath1[i]->state);
444 for (auto &i : mpath2)
445 path->append(i->state);
446
447 pdef_->addSolutionPath(path, false, 0.0, getName());
448 solved = true;
449 break;
450 }
451 }
452
453 std::swap(tree, otherTree);
454 }
455
456 si_->freeState(rstate);
457 si_->freeState(xstate);
458 delete rmotion;
459 delete xmotion;
460
461 OMPL_INFORM("%s: Created %u states (%u start + %u goal)", getName().c_str(), tStart_->size() + tGoal_->size(),
462 tStart_->size(), tGoal_->size());
464}
465
467{
468 Planner::getPlannerData(data);
469
470 std::vector<Motion *> motions;
471 if (tStart_)
472 tStart_->list(motions);
473 for (auto &motion : motions)
474 {
475 if (motion->parent == nullptr)
476 data.addStartVertex(base::PlannerDataVertex(motion->state, 1));
477 else
478 {
479 data.addEdge(base::PlannerDataVertex(motion->parent->state, 1), base::PlannerDataVertex(motion->state, 1));
480 }
481 }
482
483 motions.clear();
484 if (tGoal_)
485 tGoal_->list(motions);
486 for (auto &motion : motions)
487 {
488 if (motion->parent == nullptr)
489 data.addGoalVertex(base::PlannerDataVertex(motion->state, 2));
490 else
491 {
492 // The edges in the goal tree are reversed to be consistent with start tree
493 data.addEdge(base::PlannerDataVertex(motion->state, 2), base::PlannerDataVertex(motion->parent->state, 2));
494 }
495 }
496
497 // Add the edge connecting the two trees
498 if ((connectionPoint_.first != nullptr) && (connectionPoint_.second != nullptr))
499 data.addEdge(data.vertexIndex(connectionPoint_.first->state), data.vertexIndex(connectionPoint_.second->state));
500}
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
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 vertexIndex(const PlannerDataVertex &v) const
Return the index for the vertex associated with the given data. INVALID_INDEX is returned if this ver...
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
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 in the search tree.
Definition BiTRRT.h:184
base::State * state
The state contained by the motion.
Definition BiTRRT.h:197
Motion * parent
The parent motion in the exploration tree.
Definition BiTRRT.h:200
const base::State * root
Pointer to the root of the tree this motion is contained in.
Definition BiTRRT.h:207
bool transitionTest(const base::Cost &motionCost)
Transition test that filters transitions based on the motion cost. If the motion cost is near or belo...
Definition BiTRRT.cpp:179
bool minExpansionControl(double dist)
Use frontier node ratio to filter nodes that do not add new information to the search tree.
Definition BiTRRT.cpp:206
void setFrontierNodeRatio(double frontierNodeRatio)
Set the ratio between adding non-frontier nodes to frontier nodes. For example: .1 is one non-frontie...
Definition BiTRRT.h:157
double frontierThreshold_
The distance between an existing state and a new state that qualifies it as a frontier state.
Definition BiTRRT.h:281
TreeData tStart_
The start tree.
Definition BiTRRT.h:304
void setFrontierThreshold(double frontierThreshold)
Set the distance between a new state and the nearest neighbor that qualifies a state as being a front...
Definition BiTRRT.h:142
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition BiTRRT.cpp:97
double getFrontierNodeRatio() const
Get the ratio between adding non-frontier nodes to frontier nodes.
Definition BiTRRT.h:164
GrowResult
The result of a call to extendTree.
Definition BiTRRT.h:233
@ SUCCESS
The desired state was reached during extension.
Definition BiTRRT.h:239
@ FAILED
No extension was possible.
Definition BiTRRT.h:235
@ ADVANCED
Progress was made toward extension.
Definition BiTRRT.h:237
double getInitTemperature() const
Get the initial temperature at the start of planning.
Definition BiTRRT.h:135
double connectionRange_
The range at which the algorithm will attempt to connect the two trees.
Definition BiTRRT.h:297
BiTRRT(const base::SpaceInformationPtr &si)
Constructor.
Definition BiTRRT.cpp:45
ompl::base::OptimizationObjectivePtr opt_
The objective (cost function) being optimized.
Definition BiTRRT.h:310
base::Cost worstCost_
The least desirable (e.g., maximum) cost value in the search tree.
Definition BiTRRT.h:271
base::Cost costThreshold_
All motion costs must be better than this cost (default is infinity).
Definition BiTRRT.h:274
TreeData tGoal_
The goal tree.
Definition BiTRRT.h:307
double getCostThreshold() const
Get the cost threshold (default is infinity). Any motion cost that is not better than this cost (acco...
Definition BiTRRT.h:122
double tempChangeFactor_
The factor by which the temperature is increased after a failed transition test.
Definition BiTRRT.h:265
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states).
Definition BiTRRT.h:255
Motion * addMotion(const base::State *state, TreeData &tree, Motion *parent=nullptr)
Add a state to the given tree. The motion created is returned.
Definition BiTRRT.cpp:160
double initTemperature_
The temperature that planning begins at.
Definition BiTRRT.h:277
bool connectTrees(Motion *nmotion, TreeData &tree, Motion *xmotion)
Attempt to connect tree to nmotion, which is in the other tree. xmotion is scratch space and will be ...
Definition BiTRRT.cpp:271
void setTempChangeFactor(double factor)
Set the factor by which the temperature is increased after a failed transition test....
Definition BiTRRT.h:99
void setCostThreshold(double maxCost)
Set the cost threshold (default is infinity). Any motion cost that is not better than this cost (acco...
Definition BiTRRT.h:114
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition BiTRRT.h:261
double getFrontierThreshold() const
Get the distance between a new state and the nearest neighbor that qualifies a state as being a front...
Definition BiTRRT.h:149
GrowResult extendTree(Motion *toMotion, TreeData &tree, Motion *&result)
Extend tree toward the state in rmotion. Store the result of the extension, if any,...
Definition BiTRRT.cpp:263
double temp_
The current temperature.
Definition BiTRRT.h:287
std::shared_ptr< NearestNeighbors< Motion * > > TreeData
The nearest-neighbors data structure that contains the entire the tree of motions generated during pl...
Definition BiTRRT.h:215
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition BiTRRT.cpp:115
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 BiTRRT.cpp:466
base::Cost bestCost_
The most desirable (e.g., minimum) cost value in the search tree.
Definition BiTRRT.h:268
void freeMemory()
Free all memory allocated during planning.
Definition BiTRRT.cpp:70
double frontierCount_
A count of the number of frontier nodes in the trees.
Definition BiTRRT.h:293
void setRange(double distance)
Set the maximum possible length of any one motion in the search tree. Very short/long motions may inh...
Definition BiTRRT.h:83
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 BiTRRT.cpp:333
double frontierNodeRatio_
The target ratio of non-frontier nodes to frontier nodes.
Definition BiTRRT.h:284
double getRange() const
Get the range the planner is using.
Definition BiTRRT.h:89
void setInitTemperature(double initTemperature)
Set the initial temperature at the start of planning. Should be high to allow for initial exploration...
Definition BiTRRT.h:129
double nonfrontierCount_
A count of the number of non-frontier nodes in the trees.
Definition BiTRRT.h:290
double getTempChangeFactor() const
Get the factor by which the temperature is increased after a failed transition.
Definition BiTRRT.h:106
std::pair< Motion *, Motion * > connectionPoint_
The most recent connection point for the two trees. Used for PlannerData computation.
Definition BiTRRT.h:301
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
#define OMPL_DEBUG(fmt,...)
Log a formatted debugging string.
Definition Console.h:70
This namespace contains sampling based planning routines shared by both planning under geometric cons...
static const double COST_MAX_MOTION_LENGTH_AS_SPACE_EXTENT_FRACTION
For cost-based planners it has been observed that smaller ranges are typically suitable....
A class to store the exit status of Planner::solve().
@ INVALID_START
Invalid start state or no start state specified.
@ EXACT_SOLUTION
The planner found an exact solution.
@ INVALID_GOAL
Invalid goal state.
@ UNRECOGNIZED_GOAL_TYPE
The goal is of a type that a planner does not recognize.
@ TIMEOUT
The planner failed to find a solution.