Loading...
Searching...
No Matches
RRTConnect.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
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 Willow Garage 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: Ioan Sucan */
36
37#include "ompl/geometric/planners/rrt/RRTConnect.h"
38#include "ompl/base/goals/GoalSampleableRegion.h"
39#include "ompl/tools/config/SelfConfig.h"
40#include "ompl/util/String.h"
41
42ompl::geometric::RRTConnect::RRTConnect(const base::SpaceInformationPtr &si, bool addIntermediateStates)
43 : base::Planner(si, addIntermediateStates ? "RRTConnectIntermediate" : "RRTConnect")
44{
45 specs_.recognizedGoal = base::GOAL_SAMPLEABLE_REGION;
46 specs_.directed = true;
47
48 Planner::declareParam<double>("range", this, &RRTConnect::setRange, &RRTConnect::getRange, "0.:1.:10000.");
49 Planner::declareParam<bool>("intermediate_states", this, &RRTConnect::setIntermediateStates,
51
52 connectionPoint_ = std::make_pair<base::State *, base::State *>(nullptr, nullptr);
53 distanceBetweenTrees_ = std::numeric_limits<double>::infinity();
54 addIntermediateStates_ = addIntermediateStates;
55}
56
57ompl::geometric::RRTConnect::~RRTConnect()
58{
59 freeMemory();
60}
61
63{
64 Planner::setup();
67
68 if (!tStart_)
70 if (!tGoal_)
72 tStart_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
73 tGoal_->setDistanceFunction([this](const Motion *a, const Motion *b) { return distanceFunction(a, b); });
74}
75
77{
78 std::vector<Motion *> motions;
79
80 if (tStart_)
81 {
82 tStart_->list(motions);
83 for (auto &motion : motions)
84 {
85 if (motion->state != nullptr)
86 si_->freeState(motion->state);
87 delete motion;
88 }
89 }
90
91 if (tGoal_)
92 {
93 tGoal_->list(motions);
94 for (auto &motion : motions)
95 {
96 if (motion->state != nullptr)
97 si_->freeState(motion->state);
98 delete motion;
99 }
100 }
101}
102
104{
105 Planner::clear();
106 sampler_.reset();
107 freeMemory();
108 if (tStart_)
109 tStart_->clear();
110 if (tGoal_)
111 tGoal_->clear();
112 connectionPoint_ = std::make_pair<base::State *, base::State *>(nullptr, nullptr);
113 distanceBetweenTrees_ = std::numeric_limits<double>::infinity();
114}
115
117 Motion *rmotion)
118{
119 /* find closest state in the tree */
120 Motion *nmotion = tree->nearest(rmotion);
121
122 /* assume we can reach the state we go towards */
123 bool reach = true;
124
125 /* find state to add */
126 base::State *dstate = rmotion->state;
127 double d = si_->distance(nmotion->state, rmotion->state);
128 if (d > maxDistance_)
129 {
130 si_->getStateSpace()->interpolate(nmotion->state, rmotion->state, maxDistance_ / d, tgi.xstate);
131
132 /* Check if we have moved at all. Due to some stranger state spaces (e.g., the constrained state spaces),
133 * interpolate can fail and no progress is made. Without this check, the algorithm gets stuck in a loop as it
134 * thinks it is making progress, when none is actually occurring. */
135 if (si_->equalStates(nmotion->state, tgi.xstate))
136 return TRAPPED;
137
138 dstate = tgi.xstate;
139 reach = false;
140 }
141
142 bool validMotion = tgi.start ? si_->checkMotion(nmotion->state, dstate) :
143 si_->isValid(dstate) && si_->checkMotion(dstate, nmotion->state);
144
145 if (!validMotion)
146 return TRAPPED;
147
149 {
150 const base::State *astate = tgi.start ? nmotion->state : dstate;
151 const base::State *bstate = tgi.start ? dstate : nmotion->state;
152
153 std::vector<base::State *> states;
154 const unsigned int count = si_->getStateSpace()->validSegmentCount(astate, bstate);
155
156 if (si_->getMotionStates(astate, bstate, states, count, true, true))
157 {
158 // if coming from start, don't add the start state (start->goal)
159 if (tgi.start)
160 si_->freeState(states[0]);
161 // if coming from the goal, don't add the start state (goal->start)
162 else
163 si_->freeState(states[states.size() - 1]);
164 }
165
166 // Add states forwards if from start, backwards if from goal
167 const auto &add_state = [&](const auto &state)
168 {
169 auto *motion = new Motion;
170 motion->state = state;
171 motion->parent = nmotion;
172 motion->root = nmotion->root;
173 tree->add(motion);
174 nmotion = motion;
175 };
176
177 if (tgi.start)
178 std::for_each(++std::begin(states), std::end(states), add_state);
179 else
180 std::for_each(++std::rbegin(states), std::rend(states), add_state);
181
182 tgi.xmotion = nmotion;
183 }
184 else
185 {
186 auto *motion = new Motion(si_);
187 si_->copyState(motion->state, dstate);
188 motion->parent = nmotion;
189 motion->root = nmotion->root;
190 tree->add(motion);
191
192 tgi.xmotion = motion;
193 }
194
195 return reach ? REACHED : ADVANCED;
196}
197
199{
201 auto *goal = dynamic_cast<base::GoalSampleableRegion *>(pdef_->getGoal().get());
202
203 if (goal == nullptr)
204 {
205 OMPL_ERROR("%s: Unknown type of goal", getName().c_str());
207 }
208
209 while (const base::State *st = pis_.nextStart())
210 {
211 auto *motion = new Motion(si_);
212 si_->copyState(motion->state, st);
213 motion->root = motion->state;
214 tStart_->add(motion);
215 }
216
217 if (tStart_->size() == 0)
218 {
219 OMPL_ERROR("%s: Motion planning start tree could not be initialized!", getName().c_str());
221 }
222
223 if (!goal->couldSample())
224 {
225 OMPL_ERROR("%s: Insufficient states in sampleable goal region", getName().c_str());
227 }
228
229 if (!sampler_)
230 sampler_ = si_->allocStateSampler();
231
232 OMPL_INFORM("%s: Starting planning with %d states already in datastructure", getName().c_str(),
233 (int)(tStart_->size() + tGoal_->size()));
234
235 TreeGrowingInfo tgi;
236 tgi.xstate = si_->allocState();
237
238 Motion *approxsol = nullptr;
239 double approxdif = std::numeric_limits<double>::infinity();
240 auto *rmotion = new Motion(si_);
241 base::State *rstate = rmotion->state;
242 bool solved = false;
244
245 while (!ptc)
246 {
247 TreeData &tree = startTree_ ? tStart_ : tGoal_;
248 tgi.start = startTree_;
250 TreeData &otherTree = startTree_ ? tStart_ : tGoal_;
251
252 if (tGoal_->size() == 0 || pis_.getSampledGoalsCount() < tGoal_->size() / 2)
253 {
254 const base::State *st = tGoal_->size() == 0 ? pis_.nextGoal(ptc) : pis_.nextGoal();
255 if (st != nullptr)
256 {
257 auto *motion = new Motion(si_);
258 si_->copyState(motion->state, st);
259 motion->root = motion->state;
260 tGoal_->add(motion);
261 }
262
263 if (tGoal_->size() == 0)
264 {
265 OMPL_ERROR("%s: Unable to sample any valid states for goal tree", getName().c_str());
267 break;
268 }
269 }
270
271 /* sample random state */
272 sampler_->sampleUniform(rstate);
273
274 GrowState gs = growTree(tree, tgi, rmotion);
275
276 if (gs != TRAPPED)
277 {
278 /* remember which motion was just added */
279 Motion *addedMotion = tgi.xmotion;
280
281 /* attempt to connect trees */
282
283 /* if reached, it means we used rstate directly, no need to copy again */
284 if (gs != REACHED)
285 si_->copyState(rstate, tgi.xstate);
286
287 tgi.start = startTree_;
288
289 /* if initial progress cannot be done from the otherTree, restore tgi.start */
290 GrowState gsc = growTree(otherTree, tgi, rmotion);
291 if (gsc == TRAPPED)
292 tgi.start = !tgi.start;
293
294 while (gsc == ADVANCED)
295 gsc = growTree(otherTree, tgi, rmotion);
296
297 /* update distance between trees */
298 const double newDist = tree->getDistanceFunction()(addedMotion, otherTree->nearest(addedMotion));
299 if (newDist < distanceBetweenTrees_)
300 {
301 distanceBetweenTrees_ = newDist;
302 // OMPL_INFORM("Estimated distance to go: %f", distanceBetweenTrees_);
303 }
304
305 Motion *startMotion = tgi.start ? tgi.xmotion : addedMotion;
306 Motion *goalMotion = tgi.start ? addedMotion : tgi.xmotion;
307
308 /* if we connected the trees in a valid way (start and goal pair is valid)*/
309 if (gsc == REACHED && goal->isStartGoalPairValid(startMotion->root, goalMotion->root))
310 {
311 // it must be the case that either the start tree or the goal tree has made some progress
312 // so one of the parents is not nullptr. We go one step 'back' to avoid having a duplicate state
313 // on the solution path
314 if (startMotion->parent != nullptr)
315 startMotion = startMotion->parent;
316 else
317 goalMotion = goalMotion->parent;
318
319 connectionPoint_ = std::make_pair(startMotion->state, goalMotion->state);
320
321 /* construct the solution path */
322 Motion *solution = startMotion;
323 std::vector<Motion *> mpath1;
324 while (solution != nullptr)
325 {
326 mpath1.push_back(solution);
327 solution = solution->parent;
328 }
329
330 solution = goalMotion;
331 std::vector<Motion *> mpath2;
332 while (solution != nullptr)
333 {
334 mpath2.push_back(solution);
335 solution = solution->parent;
336 }
337
338 auto path(std::make_shared<PathGeometric>(si_));
339 path->getStates().reserve(mpath1.size() + mpath2.size());
340 for (int i = mpath1.size() - 1; i >= 0; --i)
341 path->append(mpath1[i]->state);
342 for (auto &i : mpath2)
343 path->append(i->state);
344
345 pdef_->addSolutionPath(path, false, 0.0, getName());
346 solved = true;
347 break;
348 }
349 else
350 {
351 // We didn't reach the goal, but if we were extending the start
352 // tree, then we can mark/improve the approximate path so far.
353 if (tgi.start)
354 {
355 // We were working from the startTree.
356 double dist = 0.0;
357 goal->isSatisfied(tgi.xmotion->state, &dist);
358 if (dist < approxdif)
359 {
360 approxdif = dist;
361 approxsol = tgi.xmotion;
362 }
363 }
364 }
365 }
366 }
367
368 si_->freeState(tgi.xstate);
369 si_->freeState(rstate);
370 delete rmotion;
371
372 OMPL_INFORM("%s: Created %u states (%u start + %u goal)", getName().c_str(), tStart_->size() + tGoal_->size(),
373 tStart_->size(), tGoal_->size());
374
375 if (approxsol && !solved)
376 {
377 /* construct the solution path */
378 std::vector<Motion *> mpath;
379 while (approxsol != nullptr)
380 {
381 mpath.push_back(approxsol);
382 approxsol = approxsol->parent;
383 }
384
385 auto path(std::make_shared<PathGeometric>(si_));
386 for (int i = mpath.size() - 1; i >= 0; --i)
387 path->append(mpath[i]->state);
388 pdef_->addSolutionPath(path, true, approxdif, getName());
390 }
391
392 return solved ? base::PlannerStatus::EXACT_SOLUTION : status;
393}
394
396{
397 Planner::getPlannerData(data);
398
399 std::vector<Motion *> motions;
400 if (tStart_)
401 tStart_->list(motions);
402
403 for (auto &motion : motions)
404 {
405 if (motion->parent == nullptr)
406 data.addStartVertex(base::PlannerDataVertex(motion->state, 1));
407 else
408 {
409 data.addEdge(base::PlannerDataVertex(motion->parent->state, 1), base::PlannerDataVertex(motion->state, 1));
410 }
411 }
412
413 motions.clear();
414 if (tGoal_)
415 tGoal_->list(motions);
416
417 for (auto &motion : motions)
418 {
419 if (motion->parent == nullptr)
420 data.addGoalVertex(base::PlannerDataVertex(motion->state, 2));
421 else
422 {
423 // The edges in the goal tree are reversed to be consistent with start tree
424 data.addEdge(base::PlannerDataVertex(motion->state, 2), base::PlannerDataVertex(motion->parent->state, 2));
425 }
426 }
427
428 // Add the edge connecting the two trees
429 data.addEdge(data.vertexIndex(connectionPoint_.first), data.vertexIndex(connectionPoint_.second));
430
431 // Add some info.
432 data.properties["approx goal distance REAL"] = ompl::toString(distanceBetweenTrees_);
433}
Abstract definition of a goal region that can be sampled.
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...
std::map< std::string, std::string > properties
Any extra properties (key-value pairs) the planner can set.
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.
Definition RRTConnect.h:122
std::pair< base::State *, base::State * > connectionPoint_
The pair of states in each tree connected during planning. Used for PlannerData computation.
Definition RRTConnect.h:193
bool startTree_
A flag that toggles between expanding the start tree (true) or goal tree (false).
Definition RRTConnect.h:181
GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion)
Grow a tree towards a random state.
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition RRTConnect.h:184
double getRange() const
Get the range the planner is using.
Definition RRTConnect.h:100
void setRange(double distance)
Set the range the planner is supposed to use.
Definition RRTConnect.h:94
GrowState
The state of the tree after an attempt to extend it.
Definition RRTConnect.h:150
@ ADVANCED
progress has been made towards the randomly sampled state
Definition RRTConnect.h:154
@ TRAPPED
no progress has been made
Definition RRTConnect.h:152
@ REACHED
the randomly sampled state was reached
Definition RRTConnect.h:156
bool addIntermediateStates_
Flag indicating whether intermediate states are added to the built tree of motions.
Definition RRTConnect.h:187
void freeMemory()
Free the memory allocated by this planner.
std::shared_ptr< NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions.
Definition RRTConnect.h:138
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
bool getIntermediateStates() const
Return true if the intermediate states generated along motions are to be added to the tree itself.
Definition RRTConnect.h:77
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
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 setIntermediateStates(bool addIntermediateStates)
Specify whether the intermediate states generated along motions are to be added to the tree itself.
Definition RRTConnect.h:84
TreeData tStart_
The start tree.
Definition RRTConnect.h:175
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...
double distanceBetweenTrees_
Distance between the nearest pair of start tree and goal tree nodes.
Definition RRTConnect.h:196
base::StateSamplerPtr sampler_
State sampler.
Definition RRTConnect.h:172
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states).
Definition RRTConnect.h:163
RRTConnect(const base::SpaceInformationPtr &si, bool addIntermediateStates=false)
Constructor.
TreeData tGoal_
The goal tree.
Definition RRTConnect.h:178
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...
@ GOAL_SAMPLEABLE_REGION
This bit is set if casting to sampleable goal regions (ompl::base::GoalSampleableRegion) is possible.
Definition GoalTypes.h:56
std::string toString(float val)
convert float to string using classic "C" locale semantics
Definition String.cpp:82
A class to store the exit status of Planner::solve().
StatusType
The possible values of the status returned by a planner.
@ 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.
@ APPROXIMATE_SOLUTION
The planner found an approximate solution.
@ TIMEOUT
The planner failed to find a solution.
Information attached to growing a tree of motions (used internally).
Definition RRTConnect.h:142